soc/cores/cpu/rocket: Support for 64-bit RocketChip (experimental)
Simulate a Rocket-based 64-bit LiteX SoC with the following command: litex/tools/litex_sim.py [--with-sdram] --cpu-type=rocket NOTE: Synthesizes to FPGA and passes timing at 50MHz on nexys4ddr (with vivado) and ecp5versa (with yosys/trellis/nextpnr), but at this time does not yet properly initialize physical on-board DRAM. On ecp5versa, using '--with-ethernet', up to 97% of the available TRELLIS_SLICE capacity is utilized. Signed-off-by: Gabriel Somlo <gsomlo@gmail.com>
This commit is contained in:
parent
3de49118d9
commit
1a530cf27d
|
@ -47,7 +47,7 @@ class _CRG(Module):
|
|||
# BaseSoC ------------------------------------------------------------------------------------------
|
||||
|
||||
class BaseSoC(SoCSDRAM):
|
||||
def __init__(self, sys_clk_freq=int(100e6), **kwargs):
|
||||
def __init__(self, sys_clk_freq=int(50e6), **kwargs):
|
||||
platform = nexys4ddr.Platform()
|
||||
SoCSDRAM.__init__(self, platform, clk_freq=sys_clk_freq,
|
||||
integrated_rom_size=0x8000,
|
||||
|
|
|
@ -73,7 +73,7 @@ class _CRG(Module):
|
|||
# BaseSoC ------------------------------------------------------------------------------------------
|
||||
|
||||
class BaseSoC(SoCSDRAM):
|
||||
def __init__(self, sys_clk_freq=int(75e6), toolchain="diamond", **kwargs):
|
||||
def __init__(self, sys_clk_freq=int(50e6), toolchain="diamond", **kwargs):
|
||||
platform = versa_ecp5.Platform(toolchain=toolchain)
|
||||
SoCSDRAM.__init__(self, platform, clk_freq=sys_clk_freq,
|
||||
integrated_rom_size=0x8000,
|
||||
|
|
|
@ -27,6 +27,7 @@ $(OBJS_SIM): %.o: $(SRC_DIR)/%.c
|
|||
.PHONY: sim
|
||||
sim: mkdir $(OBJS_SIM)
|
||||
verilator -Wno-fatal -O3 $(CC_SRCS) --top-module dut --exe \
|
||||
-DPRINTF_COND=0 \
|
||||
$(SRCS_SIM_CPP) $(OBJS_SIM) \
|
||||
--top-module dut \
|
||||
$(if $(THREADS), --threads $(THREADS),) \
|
||||
|
|
|
@ -3,3 +3,4 @@ from litex.soc.cores.cpu.mor1kx import MOR1KX
|
|||
from litex.soc.cores.cpu.picorv32 import PicoRV32
|
||||
from litex.soc.cores.cpu.vexriscv import VexRiscv
|
||||
from litex.soc.cores.cpu.minerva import Minerva
|
||||
from litex.soc.cores.cpu.rocket import RocketRV64
|
||||
|
|
|
@ -0,0 +1 @@
|
|||
from litex.soc.cores.cpu.rocket.core import RocketRV64
|
|
@ -0,0 +1,242 @@
|
|||
# litex/soc/cores/cpu/rocket/core.py
|
||||
# Rocket Chip core support for the LiteX SoC.
|
||||
#
|
||||
# Author: Gabriel L. Somlo <somlo@cmu.edu>
|
||||
# Copyright (c) 2019, Carnegie Mellon University
|
||||
# All rights reserved.
|
||||
#
|
||||
# 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.
|
||||
#
|
||||
# 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.
|
||||
|
||||
import os
|
||||
|
||||
from migen import *
|
||||
|
||||
from litex.soc.interconnect import axi
|
||||
from litex.soc.interconnect import wishbone
|
||||
|
||||
CPU_VARIANTS = ["standard"]
|
||||
|
||||
GCC_FLAGS = {
|
||||
"standard": "-march=rv64imac -mabi=lp64 ",
|
||||
}
|
||||
|
||||
class RocketRV64(Module):
|
||||
@property
|
||||
def name(self):
|
||||
return "rocket"
|
||||
|
||||
@property
|
||||
def endianness(self):
|
||||
return "little"
|
||||
|
||||
@property
|
||||
def gcc_triple(self):
|
||||
return ("riscv64-unknown-elf")
|
||||
|
||||
@property
|
||||
def gcc_flags(self):
|
||||
flags = "-mno-save-restore "
|
||||
flags += GCC_FLAGS[self.variant]
|
||||
flags += "-D__rocket__ "
|
||||
return flags
|
||||
|
||||
@property
|
||||
def linker_output_format(self):
|
||||
return "elf64-littleriscv"
|
||||
|
||||
@property
|
||||
def reserved_interrupts(self):
|
||||
return {}
|
||||
|
||||
def __init__(self, platform, cpu_reset_addr, variant="standard"):
|
||||
assert variant in CPU_VARIANTS, "Unsupported variant %s" % variant
|
||||
assert cpu_reset_addr == 0x10000000, "cpu_reset_addr hardcoded in Chisel elaboration!"
|
||||
|
||||
self.platform = platform
|
||||
self.variant = variant
|
||||
self.reset = Signal()
|
||||
|
||||
self.interrupt = Signal(4)
|
||||
|
||||
self.mem_axi = mem_axi = axi.AXIInterface(
|
||||
data_width=64, address_width=32, id_width=4)
|
||||
self.mmio_axi = mmio_axi = axi.AXIInterface(
|
||||
data_width=64, address_width=32, id_width=4)
|
||||
|
||||
self.mem_wb = mem_wb = wishbone.Interface(data_width=64, adr_width=29)
|
||||
self.mmio_wb = mmio_wb = wishbone.Interface(data_width=64, adr_width=29)
|
||||
|
||||
self.ibus = ibus = wishbone.Interface()
|
||||
self.dbus = dbus = wishbone.Interface()
|
||||
|
||||
|
||||
# # #
|
||||
|
||||
self.specials += Instance("ExampleRocketSystem",
|
||||
# clock, reset
|
||||
i_clock=ClockSignal(),
|
||||
i_reset=ResetSignal() | self.reset,
|
||||
|
||||
# debug (ignored)
|
||||
#o_debug_clockeddmi_dmi_req_ready=,
|
||||
i_debug_clockeddmi_dmi_req_valid=0,
|
||||
i_debug_clockeddmi_dmi_req_bits_addr=0,
|
||||
i_debug_clockeddmi_dmi_req_bits_data=0,
|
||||
i_debug_clockeddmi_dmi_req_bits_op=0,
|
||||
i_debug_clockeddmi_dmi_resp_ready=0,
|
||||
#o_debug_clockeddmi_dmi_resp_valid=,
|
||||
#o_debug_clockeddmi_dmi_resp_bits_data=,
|
||||
#o_debug_clockeddmi_dmi_resp_bits_resp=,
|
||||
i_debug_clockeddmi_dmiClock=0,
|
||||
i_debug_clockeddmi_dmiReset=0,
|
||||
#o_debug_ndreset=,
|
||||
#o_debug_dmactive=,
|
||||
|
||||
|
||||
# irq
|
||||
i_interrupts=self.interrupt,
|
||||
|
||||
# axi memory (L1-cached)
|
||||
i_mem_axi4_0_aw_ready=mem_axi.aw.ready,
|
||||
o_mem_axi4_0_aw_valid=mem_axi.aw.valid,
|
||||
o_mem_axi4_0_aw_bits_id=mem_axi.aw.id,
|
||||
o_mem_axi4_0_aw_bits_addr=mem_axi.aw.addr,
|
||||
o_mem_axi4_0_aw_bits_len=mem_axi.aw.len,
|
||||
o_mem_axi4_0_aw_bits_size=mem_axi.aw.size,
|
||||
o_mem_axi4_0_aw_bits_burst=mem_axi.aw.burst,
|
||||
o_mem_axi4_0_aw_bits_lock=mem_axi.aw.lock,
|
||||
o_mem_axi4_0_aw_bits_cache=mem_axi.aw.cache,
|
||||
o_mem_axi4_0_aw_bits_prot=mem_axi.aw.prot,
|
||||
o_mem_axi4_0_aw_bits_qos=mem_axi.aw.qos,
|
||||
|
||||
i_mem_axi4_0_w_ready=mem_axi.w.ready,
|
||||
o_mem_axi4_0_w_valid=mem_axi.w.valid,
|
||||
o_mem_axi4_0_w_bits_data=mem_axi.w.data,
|
||||
o_mem_axi4_0_w_bits_strb=mem_axi.w.strb,
|
||||
o_mem_axi4_0_w_bits_last=mem_axi.w.last,
|
||||
|
||||
o_mem_axi4_0_b_ready=mem_axi.b.ready,
|
||||
i_mem_axi4_0_b_valid=mem_axi.b.valid,
|
||||
i_mem_axi4_0_b_bits_id=mem_axi.b.id,
|
||||
i_mem_axi4_0_b_bits_resp=mem_axi.b.resp,
|
||||
|
||||
i_mem_axi4_0_ar_ready=mem_axi.ar.ready,
|
||||
o_mem_axi4_0_ar_valid=mem_axi.ar.valid,
|
||||
o_mem_axi4_0_ar_bits_id=mem_axi.ar.id,
|
||||
o_mem_axi4_0_ar_bits_addr=mem_axi.ar.addr,
|
||||
o_mem_axi4_0_ar_bits_len=mem_axi.ar.len,
|
||||
o_mem_axi4_0_ar_bits_size=mem_axi.ar.size,
|
||||
o_mem_axi4_0_ar_bits_burst=mem_axi.ar.burst,
|
||||
o_mem_axi4_0_ar_bits_lock=mem_axi.ar.lock,
|
||||
o_mem_axi4_0_ar_bits_cache=mem_axi.ar.cache,
|
||||
o_mem_axi4_0_ar_bits_prot=mem_axi.ar.prot,
|
||||
o_mem_axi4_0_ar_bits_qos=mem_axi.ar.qos,
|
||||
|
||||
o_mem_axi4_0_r_ready=mem_axi.r.ready,
|
||||
i_mem_axi4_0_r_valid=mem_axi.r.valid,
|
||||
i_mem_axi4_0_r_bits_id=mem_axi.r.id,
|
||||
i_mem_axi4_0_r_bits_data=mem_axi.r.data,
|
||||
i_mem_axi4_0_r_bits_resp=mem_axi.r.resp,
|
||||
i_mem_axi4_0_r_bits_last=mem_axi.r.last,
|
||||
|
||||
# axi mmio (not cached)
|
||||
i_mmio_axi4_0_aw_ready=mmio_axi.aw.ready,
|
||||
o_mmio_axi4_0_aw_valid=mmio_axi.aw.valid,
|
||||
o_mmio_axi4_0_aw_bits_id=mmio_axi.aw.id,
|
||||
o_mmio_axi4_0_aw_bits_addr=mmio_axi.aw.addr,
|
||||
o_mmio_axi4_0_aw_bits_len=mmio_axi.aw.len,
|
||||
o_mmio_axi4_0_aw_bits_size=mmio_axi.aw.size,
|
||||
o_mmio_axi4_0_aw_bits_burst=mmio_axi.aw.burst,
|
||||
o_mmio_axi4_0_aw_bits_lock=mmio_axi.aw.lock,
|
||||
o_mmio_axi4_0_aw_bits_cache=mmio_axi.aw.cache,
|
||||
o_mmio_axi4_0_aw_bits_prot=mmio_axi.aw.prot,
|
||||
o_mmio_axi4_0_aw_bits_qos=mmio_axi.aw.qos,
|
||||
|
||||
i_mmio_axi4_0_w_ready=mmio_axi.w.ready,
|
||||
o_mmio_axi4_0_w_valid=mmio_axi.w.valid,
|
||||
o_mmio_axi4_0_w_bits_data=mmio_axi.w.data,
|
||||
o_mmio_axi4_0_w_bits_strb=mmio_axi.w.strb,
|
||||
o_mmio_axi4_0_w_bits_last=mmio_axi.w.last,
|
||||
|
||||
o_mmio_axi4_0_b_ready=mmio_axi.b.ready,
|
||||
i_mmio_axi4_0_b_valid=mmio_axi.b.valid,
|
||||
i_mmio_axi4_0_b_bits_id=mmio_axi.b.id,
|
||||
i_mmio_axi4_0_b_bits_resp=mmio_axi.b.resp,
|
||||
|
||||
i_mmio_axi4_0_ar_ready=mmio_axi.ar.ready,
|
||||
o_mmio_axi4_0_ar_valid=mmio_axi.ar.valid,
|
||||
o_mmio_axi4_0_ar_bits_id=mmio_axi.ar.id,
|
||||
o_mmio_axi4_0_ar_bits_addr=mmio_axi.ar.addr,
|
||||
o_mmio_axi4_0_ar_bits_len=mmio_axi.ar.len,
|
||||
o_mmio_axi4_0_ar_bits_size=mmio_axi.ar.size,
|
||||
o_mmio_axi4_0_ar_bits_burst=mmio_axi.ar.burst,
|
||||
o_mmio_axi4_0_ar_bits_lock=mmio_axi.ar.lock,
|
||||
o_mmio_axi4_0_ar_bits_cache=mmio_axi.ar.cache,
|
||||
o_mmio_axi4_0_ar_bits_prot=mmio_axi.ar.prot,
|
||||
o_mmio_axi4_0_ar_bits_qos=mmio_axi.ar.qos,
|
||||
|
||||
o_mmio_axi4_0_r_ready=mmio_axi.r.ready,
|
||||
i_mmio_axi4_0_r_valid=mmio_axi.r.valid,
|
||||
i_mmio_axi4_0_r_bits_id=mmio_axi.r.id,
|
||||
i_mmio_axi4_0_r_bits_data=mmio_axi.r.data,
|
||||
i_mmio_axi4_0_r_bits_resp=mmio_axi.r.resp,
|
||||
i_mmio_axi4_0_r_bits_last=mmio_axi.r.last,
|
||||
)
|
||||
|
||||
# adapt axi interfaces to wishbone
|
||||
mem_a2w = ResetInserter()(
|
||||
axi.AXI2Wishbone(mem_axi, mem_wb, base_address=0))
|
||||
mmio_a2w = ResetInserter()(
|
||||
axi.AXI2Wishbone(mmio_axi, mmio_wb, base_address=0))
|
||||
# NOTE: AXI2Wishbone FSMs must be reset with the CPU!
|
||||
self.comb += [
|
||||
mem_a2w.reset.eq(ResetSignal() | self.reset),
|
||||
mmio_a2w.reset.eq(ResetSignal() | self.reset),
|
||||
]
|
||||
|
||||
# down-convert wishbone from 64 to 32 bit data width
|
||||
mem_dc = wishbone.Converter(mem_wb, ibus)
|
||||
mmio_dc = wishbone.Converter(mmio_wb, dbus)
|
||||
|
||||
self.submodules += mem_a2w, mem_dc, mmio_a2w, mmio_dc
|
||||
|
||||
# add verilog sources
|
||||
self.add_sources(platform)
|
||||
|
||||
@staticmethod
|
||||
def add_sources(platform):
|
||||
vdir = os.path.join(
|
||||
os.path.abspath(os.path.dirname(__file__)), "verilog")
|
||||
platform.add_sources(
|
||||
os.path.join(vdir, "generated-src"),
|
||||
"freechips.rocketchip.system.LitexConfig.v",
|
||||
"freechips.rocketchip.system.LitexConfig.behav_srams.v",
|
||||
)
|
||||
platform.add_sources(
|
||||
os.path.join(vdir, "vsrc"),
|
||||
"plusarg_reader.v",
|
||||
"AsyncResetReg.v",
|
||||
"EICG_wrapper.v",
|
||||
)
|
|
@ -167,8 +167,9 @@ class SoCCore(Module):
|
|||
csr_map = {}
|
||||
interrupt_map = {}
|
||||
mem_map = {
|
||||
"rom": 0x00000000, # (default shadow @0x80000000)
|
||||
"sram": 0x10000000, # (default shadow @0x90000000)
|
||||
# RocketChip reserves the first 256MBytes for internal use
|
||||
"rom": 0x10000000, # (default shadow @0x90000000)
|
||||
"sram": 0x20000000, # (default shadow @0xa0000000)
|
||||
"main_ram": 0x40000000, # (default shadow @0xc0000000)
|
||||
"csr": 0x60000000, # (default shadow @0xe0000000)
|
||||
}
|
||||
|
@ -267,6 +268,8 @@ class SoCCore(Module):
|
|||
self.add_cpu(vexriscv.VexRiscv(platform, self.cpu_reset_address, self.cpu_variant))
|
||||
elif cpu_type == "minerva":
|
||||
self.add_cpu(minerva.Minerva(platform, self.cpu_reset_address, self.cpu_variant))
|
||||
elif cpu_type == "rocket":
|
||||
self.add_cpu(rocket.RocketRV64(platform, self.cpu_reset_address, self.cpu_variant))
|
||||
else:
|
||||
raise ValueError("Unsupported CPU type: {}".format(cpu_type))
|
||||
self.add_csr("cpu", allow_user_defined=True)
|
||||
|
|
|
@ -0,0 +1,4 @@
|
|||
.section .text, "ax", @progbits
|
||||
.global boot_helper
|
||||
boot_helper:
|
||||
jr x13
|
|
@ -1,14 +1,57 @@
|
|||
#include <generated/csr.h>
|
||||
#include <irq.h>
|
||||
#include <uart.h>
|
||||
#include <stdio.h>
|
||||
|
||||
#ifdef __rocket__
|
||||
void plic_init(void);
|
||||
void plic_init(void)
|
||||
{
|
||||
int i;
|
||||
|
||||
// priorities for interrupt pins 1..4
|
||||
for (i = 1; i <= 4; i++)
|
||||
csr_writel(1, PLIC_BASE + 4*i);
|
||||
// enable interrupt pins 1..4
|
||||
csr_writel(0xf << 1, PLIC_ENABLED);
|
||||
// set priority threshold to 0 (any priority > 0 triggers interrupt)
|
||||
csr_writel(0, PLIC_THRSHLD);
|
||||
}
|
||||
|
||||
void isr(void);
|
||||
void isr(void)
|
||||
{
|
||||
unsigned int claim;
|
||||
|
||||
while ((claim = csr_readl(PLIC_CLAIM))) {
|
||||
switch (claim - 1) {
|
||||
case UART_INTERRUPT:
|
||||
uart_isr();
|
||||
break;
|
||||
default:
|
||||
printf("## PLIC: Unhandled claim: %d\n", claim);
|
||||
printf("# plic_enabled: %08x\n", irq_getmask());
|
||||
printf("# plic_pending: %08x\n", irq_pending());
|
||||
printf("# mepc: %016lx\n", csrr(mepc));
|
||||
printf("# mcause: %016lx\n", csrr(mcause));
|
||||
printf("# mtval: %016lx\n", csrr(mtval));
|
||||
printf("# mie: %016lx\n", csrr(mie));
|
||||
printf("# mip: %016lx\n", csrr(mip));
|
||||
printf("###########################\n\n");
|
||||
break;
|
||||
}
|
||||
csr_writel(claim, PLIC_CLAIM);
|
||||
}
|
||||
}
|
||||
#else
|
||||
void isr(void);
|
||||
void isr(void)
|
||||
{
|
||||
unsigned int irqs;
|
||||
|
||||
|
||||
irqs = irq_pending() & irq_getmask();
|
||||
|
||||
|
||||
if(irqs & (1 << UART_INTERRUPT))
|
||||
uart_isr();
|
||||
}
|
||||
#endif
|
||||
|
|
|
@ -416,6 +416,8 @@ int main(int i, char **c)
|
|||
printf("VexRiscv");
|
||||
#elif __minerva__
|
||||
printf("Minerva");
|
||||
#elif __rocket__
|
||||
printf("RocketRV64[imac]");
|
||||
#else
|
||||
printf("Unknown");
|
||||
#endif
|
||||
|
|
|
@ -30,6 +30,8 @@ __attribute__((unused)) static void cdelay(int i)
|
|||
__asm__ volatile("nop");
|
||||
#elif defined (__minerva__)
|
||||
__asm__ volatile("nop");
|
||||
#elif defined (__rocket__)
|
||||
__asm__ volatile("nop");
|
||||
#else
|
||||
#error Unsupported architecture
|
||||
#endif
|
||||
|
|
|
@ -6,6 +6,7 @@ extern "C" {
|
|||
#endif
|
||||
|
||||
#include <system.h>
|
||||
#include <generated/csr.h>
|
||||
|
||||
#ifdef __picorv32__
|
||||
// PicoRV32 has a very limited interrupt support, implemented via custom
|
||||
|
@ -28,6 +29,17 @@ extern void _irq_disable(void);
|
|||
extern void _irq_setmask(unsigned int);
|
||||
#endif
|
||||
|
||||
#ifdef __rocket__
|
||||
// The RocketChip uses a Platform-Level Interrupt Controller (PLIC) which
|
||||
// is programmed and queried via a set of MMIO registers.
|
||||
|
||||
#define PLIC_BASE 0x0c000000L // Base address and per-pin priority array
|
||||
#define PLIC_PENDING 0x0c001000L // Bit field matching currently pending pins
|
||||
#define PLIC_ENABLED 0x0c002000L // Bit field corresponding to the current mask
|
||||
#define PLIC_THRSHLD 0x0c200000L // Per-pin priority must be >= this to trigger
|
||||
#define PLIC_CLAIM 0x0c200004L // Claim & completion register address
|
||||
#endif /* __rocket__ */
|
||||
|
||||
static inline unsigned int irq_getie(void)
|
||||
{
|
||||
#if defined (__lm32__)
|
||||
|
@ -42,6 +54,8 @@ static inline unsigned int irq_getie(void)
|
|||
return (csrr(mstatus) & CSR_MSTATUS_MIE) != 0;
|
||||
#elif defined (__minerva__)
|
||||
return (csrr(mstatus) & CSR_MSTATUS_MIE) != 0;
|
||||
#elif defined (__rocket__)
|
||||
return (csrr(mstatus) & CSR_MSTATUS_MIE) != 0;
|
||||
#else
|
||||
#error Unsupported architecture
|
||||
#endif
|
||||
|
@ -65,6 +79,8 @@ static inline void irq_setie(unsigned int ie)
|
|||
if(ie) csrs(mstatus,CSR_MSTATUS_MIE); else csrc(mstatus,CSR_MSTATUS_MIE);
|
||||
#elif defined (__minerva__)
|
||||
if(ie) csrs(mstatus,CSR_MSTATUS_MIE); else csrc(mstatus,CSR_MSTATUS_MIE);
|
||||
#elif defined (__rocket__)
|
||||
if(ie) csrs(mstatus,CSR_MSTATUS_MIE); else csrc(mstatus,CSR_MSTATUS_MIE);
|
||||
#else
|
||||
#error Unsupported architecture
|
||||
#endif
|
||||
|
@ -90,6 +106,8 @@ static inline unsigned int irq_getmask(void)
|
|||
unsigned int mask;
|
||||
asm volatile ("csrr %0, %1" : "=r"(mask) : "i"(CSR_IRQ_MASK));
|
||||
return mask;
|
||||
#elif defined (__rocket__)
|
||||
return csr_readl(PLIC_ENABLED) >> 1;
|
||||
#else
|
||||
#error Unsupported architecture
|
||||
#endif
|
||||
|
@ -109,6 +127,8 @@ static inline void irq_setmask(unsigned int mask)
|
|||
asm volatile ("csrw %0, %1" :: "i"(CSR_IRQ_MASK), "r"(mask));
|
||||
#elif defined (__minerva__)
|
||||
asm volatile ("csrw %0, %1" :: "i"(CSR_IRQ_MASK), "r"(mask));
|
||||
#elif defined (__rocket__)
|
||||
csr_writel(mask << 1, PLIC_ENABLED);
|
||||
#else
|
||||
#error Unsupported architecture
|
||||
#endif
|
||||
|
@ -132,6 +152,8 @@ static inline unsigned int irq_pending(void)
|
|||
unsigned int pending;
|
||||
asm volatile ("csrr %0, %1" : "=r"(pending) : "i"(CSR_IRQ_PENDING));
|
||||
return pending;
|
||||
#elif defined (__rocket__)
|
||||
return csr_readl(PLIC_PENDING) >> 1;
|
||||
#else
|
||||
#error Unsupported architecture
|
||||
#endif
|
||||
|
|
|
@ -27,7 +27,7 @@ static inline void mtspr(unsigned long add, unsigned long val)
|
|||
#endif
|
||||
|
||||
|
||||
#if defined(__vexriscv__) || defined(__minerva__)
|
||||
#if defined(__vexriscv__) || defined(__minerva__) || defined(__rocket__)
|
||||
#include <csr-defs.h>
|
||||
#define csrr(reg) ({ unsigned long __tmp; \
|
||||
asm volatile ("csrr %0, " #reg : "=r"(__tmp)); \
|
||||
|
|
|
@ -0,0 +1,77 @@
|
|||
.global main
|
||||
.global isr
|
||||
.global _start
|
||||
|
||||
_start:
|
||||
j crt_init
|
||||
nop
|
||||
nop
|
||||
nop
|
||||
nop
|
||||
nop
|
||||
nop
|
||||
nop
|
||||
|
||||
trap_entry:
|
||||
sd x1, - 1*8(sp)
|
||||
sd x5, - 2*8(sp)
|
||||
sd x6, - 3*8(sp)
|
||||
sd x7, - 4*8(sp)
|
||||
sd x10, - 5*8(sp)
|
||||
sd x11, - 6*8(sp)
|
||||
sd x12, - 7*8(sp)
|
||||
sd x13, - 8*8(sp)
|
||||
sd x14, - 9*8(sp)
|
||||
sd x15, -10*8(sp)
|
||||
sd x16, -11*8(sp)
|
||||
sd x17, -12*8(sp)
|
||||
sd x28, -13*8(sp)
|
||||
sd x29, -14*8(sp)
|
||||
sd x30, -15*8(sp)
|
||||
sd x31, -16*8(sp)
|
||||
addi sp,sp,-16*8
|
||||
call isr
|
||||
ld x1 , 15*8(sp)
|
||||
ld x5, 14*8(sp)
|
||||
ld x6, 13*8(sp)
|
||||
ld x7, 12*8(sp)
|
||||
ld x10, 11*8(sp)
|
||||
ld x11, 10*8(sp)
|
||||
ld x12, 9*8(sp)
|
||||
ld x13, 8*8(sp)
|
||||
ld x14, 7*8(sp)
|
||||
ld x15, 6*8(sp)
|
||||
ld x16, 5*8(sp)
|
||||
ld x17, 4*8(sp)
|
||||
ld x28, 3*8(sp)
|
||||
ld x29, 2*8(sp)
|
||||
ld x30, 1*8(sp)
|
||||
ld x31, 0*8(sp)
|
||||
addi sp,sp,16*8
|
||||
mret
|
||||
.text
|
||||
|
||||
|
||||
crt_init:
|
||||
la sp, _fstack + 8
|
||||
la a0, trap_entry
|
||||
csrw mtvec, a0
|
||||
|
||||
bss_init:
|
||||
la a0, _fbss
|
||||
la a1, _ebss
|
||||
bss_loop:
|
||||
beq a0,a1,bss_done
|
||||
sd zero,0(a0)
|
||||
add a0,a0,8
|
||||
j bss_loop
|
||||
bss_done:
|
||||
|
||||
call plic_init // initialize external interrupt controller
|
||||
li a0, 0x800 // external interrupt sources only (using LiteX timer);
|
||||
// NOTE: must still enable mstatus.MIE!
|
||||
csrw mie,a0
|
||||
|
||||
call main
|
||||
inf_loop:
|
||||
j inf_loop
|
|
@ -53,6 +53,9 @@ void flush_cpu_icache(void)
|
|||
#elif defined (__minerva__)
|
||||
/* no instruction cache */
|
||||
asm volatile("nop");
|
||||
#elif defined (__rocket__)
|
||||
/* FIXME: do something useful here! */
|
||||
asm volatile("nop");
|
||||
#else
|
||||
#error Unsupported architecture
|
||||
#endif
|
||||
|
@ -95,6 +98,9 @@ void flush_cpu_dcache(void)
|
|||
#elif defined (__minerva__)
|
||||
/* no data cache */
|
||||
asm volatile("nop");
|
||||
#elif defined (__rocket__)
|
||||
/* FIXME: do something useful here! */
|
||||
asm volatile("nop");
|
||||
#else
|
||||
#error Unsupported architecture
|
||||
#endif
|
||||
|
|
Loading…
Reference in New Issue