Get PicoRV32 to execute code

1. Update LiteX to 2023.12. This update adds wishbone bus addressing
   modes. Before this update, all wishbone buses used word addressing.
   For example, 0x0 mapped to word 0, 0x0 mapped to word 1, etc. This
   caused problems with the PicoRV32 and other modules, which are byte
   addressed.
2. Use adapter to convert between byte and word addressing. The SRAM is
   word addressed. The PicoRV32 shifts the address down by two bits to
   address the correct word. The PicoRV32 core seems to expect this.
3. Add debug register output. This is not working yet.
4. Use LiteX PicoRV32 wishbone adapter instead of PicoRV32 default. This
   seems to be simpler (combinatorial not synchronous).
5. Add some documentation.
6. Seperate config to new config file.
This commit is contained in:
Peter McGoron 2024-02-25 18:58:34 +00:00
parent 3785e3498d
commit 88e3d15dd8
14 changed files with 276 additions and 330 deletions

1
.gitignore vendored
View File

@ -12,6 +12,7 @@ software/build/
obj_dir
*.fst.hier
*.swp
gateware/config.py
gateware/rtl/control_loop/control_loop_cmds.h
gateware/rtl/raster/ram_shim_cmds.h
gateware/rtl/raster/raster_cmds.h

View File

@ -38,6 +38,6 @@ COPY --chown=user:user litex/litex_setup.py /home/user
RUN mkdir /home/user/litex \
&& chmod +x litex_setup.py \
&& cd litex/ \
&& bash -c 'source ~/conda/xc7/conda/etc/profile.d/conda.sh; conda activate xc7; ../litex_setup.py --init --install --user --tag=2023.04' \
&& bash -c 'source ~/conda/xc7/conda/etc/profile.d/conda.sh; conda activate xc7; ../litex_setup.py --init --install --user --tag=2023.12' \
&& rm ../litex_setup.py

31
doc/gateware.rst Normal file
View File

@ -0,0 +1,31 @@
Copyright 2024 (C) Peter McGoron.
This file is a part of Upsilon, a free and open source software project.
For license terms, refer to the files in ``doc/copying`` in the Upsilon
source distribution.
***************************************************
This manual describes the hardware portion of Upsilon.
===============
LiteX and Migen
===============
Migen is a library that generates Verilog using Python. It uses Python
objects and methods as a DSL within Python.
LiteX is a SoC generator using Migen. LiteX includes RAM, CPU, bus logic,
etc. LiteX is very powerful but not well documented.
================
System on a Chip
================
Upsilon uses a RISC-V CPU running Linux to power most operations. It currently
uses a single-core VexRISC-V CPU running mainline Linux 5.x. How the main core
communicates with the hardware is a software issue: see /doc/software.rst .
Basic configuration of the SoC is done in the /gateware/config.py file. If
this file does not exist, copy /gateware/config.py.def to /gateware/config.py .
This is the default config.

View File

@ -289,3 +289,8 @@ Verilator. For example, if you have a file called `mod.v` in the folder
preprocessed file for you.
Another alternative is to use GNU `m4`.
## RAM Check failure on boot
You might have overloaded the CSR bus. Move some CSRs to a wishbone
bus module. See /gateware/swic.py for some simple Wishbone bus examples.

6
gateware/config.py.def Normal file
View File

@ -0,0 +1,6 @@
config = dict(
variant="a7-100",
local_ip="192.168.2.50",
remote_ip="192.168.2.100",
tftp_port=6969,
)

View File

@ -26,3 +26,4 @@ for key in j["csr_registers"]:
print(f'{key} = const({j["csr_registers"][key]["addr"]})')
print(f'pico0_ram = const({j["memories"]["pico0_ram"]["base"]})')
print(f'pico0_dbg_reg = const({j["memories"]["pico0_dbg_reg"]["base"]})')

View File

@ -38,7 +38,7 @@ class SPIMaster(Module):
:param spi_cycle_half_wait: Verilog parameter: see file.
"""
self.bus = Interface(data_width = 32, address_width=32, addressing="word")
self.bus = Interface(data_width = 32, address_width=32, addressing="byte")
self.addr_space_size = 0x10
self.comb += [

View File

@ -5,7 +5,8 @@
# source distribution.
from migen import *
from litex.soc.interconnect.wishbone import Decoder
from litex.soc.interconnect.wishbone import Decoder, Interface
from litex.gen import LiteXModule
from util import *
@ -60,10 +61,11 @@ class BasicRegion:
def __str__(self):
return str(self.to_dict())
class MemoryMap:
class MemoryMap(LiteXModule):
""" Stores the memory map of an embedded core. """
def __init__(self):
def __init__(self, masterbus):
self.regions = {}
self.masterbus = masterbus
def add_region(self, name, region):
assert name not in self.regions
@ -74,10 +76,39 @@ class MemoryMap:
import json
json.dump({k : self.regions[k].to_dict() for k in self.regions}, f)
def bus_submodule(self, masterbus):
""" Return a module that decodes the masterbus into the
slave devices according to their origin and start positions. """
slaves = [(self.regions[n].decoder(), self.regions[n].bus)
def adapt(self, target_bus):
"""
When a slave is "word" addressed (like SRAM), it accepts an index
into a array with 32-bit elements. It DOES NOT accept a byte index.
When a byte-addressed master (like the CPU) interacts with a word
addressed slave, there must be an adapter in between that converts
between the two.
PicoRV32 will read the word that contains a byte/halfword and
extract the word from it (see code assigning mem_rdata_word).
"""
assert target_bus.addressing in ["byte", "word"]
if target_bus.addressing == "byte":
return target_bus
adapter = Interface(data_width=32, address_width=32, addressing="byte")
self.comb += [
target_bus.adr.eq(adapter.adr >> 2),
target_bus.dat_w.eq(adapter.dat_w),
target_bus.we.eq(adapter.we),
target_bus.sel.eq(adapter.sel),
target_bus.cyc.eq(adapter.cyc),
target_bus.stb.eq(adapter.stb),
target_bus.cti.eq(adapter.cti),
target_bus.bte.eq(adapter.bte),
adapter.ack.eq(target_bus.ack),
adapter.dat_r.eq(target_bus.dat_r),
]
return adapter
def do_finalize(self):
slaves = [(self.regions[n].decoder(), self.adapt(self.regions[n].bus))
for n in self.regions]
return Decoder(masterbus, slaves, register=False)
self.submodules.decoder = Decoder(self.masterbus, slaves, register=True)

View File

@ -166,6 +166,38 @@ module picorv32 #(
output reg [31:0] dbg_insn_addr,
output reg [31:0] dbg_insn_opcode,
output [31:0] dbg_reg_x1,
output [31:0] dbg_reg_x2,
output [31:0] dbg_reg_x3,
output [31:0] dbg_reg_x4,
output [31:0] dbg_reg_x5,
output [31:0] dbg_reg_x6,
output [31:0] dbg_reg_x7,
output [31:0] dbg_reg_x8,
output [31:0] dbg_reg_x9,
output [31:0] dbg_reg_x10,
output [31:0] dbg_reg_x11,
output [31:0] dbg_reg_x12,
output [31:0] dbg_reg_x13,
output [31:0] dbg_reg_x14,
output [31:0] dbg_reg_x15,
output [31:0] dbg_reg_x16,
output [31:0] dbg_reg_x17,
output [31:0] dbg_reg_x18,
output [31:0] dbg_reg_x19,
output [31:0] dbg_reg_x20,
output [31:0] dbg_reg_x21,
output [31:0] dbg_reg_x22,
output [31:0] dbg_reg_x23,
output [31:0] dbg_reg_x24,
output [31:0] dbg_reg_x25,
output [31:0] dbg_reg_x26,
output [31:0] dbg_reg_x27,
output [31:0] dbg_reg_x28,
output [31:0] dbg_reg_x29,
output [31:0] dbg_reg_x30,
output [31:0] dbg_reg_x31,
// Trace Interface
output reg trace_valid,
output reg [35:0] trace_data
@ -230,40 +262,38 @@ module picorv32 #(
begin end
endtask
`ifdef DEBUGREGS
wire [31:0] dbg_reg_x0 = 0;
wire [31:0] dbg_reg_x1 = cpuregs[1];
wire [31:0] dbg_reg_x2 = cpuregs[2];
wire [31:0] dbg_reg_x3 = cpuregs[3];
wire [31:0] dbg_reg_x4 = cpuregs[4];
wire [31:0] dbg_reg_x5 = cpuregs[5];
wire [31:0] dbg_reg_x6 = cpuregs[6];
wire [31:0] dbg_reg_x7 = cpuregs[7];
wire [31:0] dbg_reg_x8 = cpuregs[8];
wire [31:0] dbg_reg_x9 = cpuregs[9];
wire [31:0] dbg_reg_x10 = cpuregs[10];
wire [31:0] dbg_reg_x11 = cpuregs[11];
wire [31:0] dbg_reg_x12 = cpuregs[12];
wire [31:0] dbg_reg_x13 = cpuregs[13];
wire [31:0] dbg_reg_x14 = cpuregs[14];
wire [31:0] dbg_reg_x15 = cpuregs[15];
wire [31:0] dbg_reg_x16 = cpuregs[16];
wire [31:0] dbg_reg_x17 = cpuregs[17];
wire [31:0] dbg_reg_x18 = cpuregs[18];
wire [31:0] dbg_reg_x19 = cpuregs[19];
wire [31:0] dbg_reg_x20 = cpuregs[20];
wire [31:0] dbg_reg_x21 = cpuregs[21];
wire [31:0] dbg_reg_x22 = cpuregs[22];
wire [31:0] dbg_reg_x23 = cpuregs[23];
wire [31:0] dbg_reg_x24 = cpuregs[24];
wire [31:0] dbg_reg_x25 = cpuregs[25];
wire [31:0] dbg_reg_x26 = cpuregs[26];
wire [31:0] dbg_reg_x27 = cpuregs[27];
wire [31:0] dbg_reg_x28 = cpuregs[28];
wire [31:0] dbg_reg_x29 = cpuregs[29];
wire [31:0] dbg_reg_x30 = cpuregs[30];
wire [31:0] dbg_reg_x31 = cpuregs[31];
`endif
// assign dbg_reg_x0 = 0;
assign dbg_reg_x1 = cpuregs[1];
assign dbg_reg_x2 = cpuregs[2];
assign dbg_reg_x3 = cpuregs[3];
assign dbg_reg_x4 = cpuregs[4];
assign dbg_reg_x5 = cpuregs[5];
assign dbg_reg_x6 = cpuregs[6];
assign dbg_reg_x7 = cpuregs[7];
assign dbg_reg_x8 = cpuregs[8];
assign dbg_reg_x9 = cpuregs[9];
assign dbg_reg_x10 = cpuregs[10];
assign dbg_reg_x11 = cpuregs[11];
assign dbg_reg_x12 = cpuregs[12];
assign dbg_reg_x13 = cpuregs[13];
assign dbg_reg_x14 = cpuregs[14];
assign dbg_reg_x15 = cpuregs[15];
assign dbg_reg_x16 = cpuregs[16];
assign dbg_reg_x17 = cpuregs[17];
assign dbg_reg_x18 = cpuregs[18];
assign dbg_reg_x19 = cpuregs[19];
assign dbg_reg_x20 = cpuregs[20];
assign dbg_reg_x21 = cpuregs[21];
assign dbg_reg_x22 = cpuregs[22];
assign dbg_reg_x23 = cpuregs[23];
assign dbg_reg_x24 = cpuregs[24];
assign dbg_reg_x25 = cpuregs[25];
assign dbg_reg_x26 = cpuregs[26];
assign dbg_reg_x27 = cpuregs[27];
assign dbg_reg_x28 = cpuregs[28];
assign dbg_reg_x29 = cpuregs[29];
assign dbg_reg_x30 = cpuregs[30];
assign dbg_reg_x31 = cpuregs[31];
// Internal PCPI Cores
@ -2533,250 +2563,3 @@ module picorv32_pcpi_div (
end
end
endmodule
/***************************************************************
* picorv32_wb
***************************************************************/
module picorv32_wb #(
parameter [ 0:0] ENABLE_COUNTERS = 1,
parameter [ 0:0] ENABLE_COUNTERS64 = 1,
parameter [ 0:0] ENABLE_REGS_16_31 = 1,
parameter [ 0:0] ENABLE_REGS_DUALPORT = 1,
parameter [ 0:0] TWO_STAGE_SHIFT = 1,
parameter [ 0:0] BARREL_SHIFTER = 0,
parameter [ 0:0] TWO_CYCLE_COMPARE = 0,
parameter [ 0:0] TWO_CYCLE_ALU = 0,
parameter [ 0:0] COMPRESSED_ISA = 0,
parameter [ 0:0] CATCH_MISALIGN = 1,
parameter [ 0:0] CATCH_ILLINSN = 1,
parameter [ 0:0] ENABLE_PCPI = 0,
parameter [ 0:0] ENABLE_MUL = 0,
parameter [ 0:0] ENABLE_FAST_MUL = 0,
parameter [ 0:0] ENABLE_DIV = 0,
parameter [ 0:0] ENABLE_IRQ = 0,
parameter [ 0:0] ENABLE_IRQ_QREGS = 1,
parameter [ 0:0] ENABLE_IRQ_TIMER = 1,
parameter [ 0:0] ENABLE_TRACE = 0,
parameter [ 0:0] REGS_INIT_ZERO = 0,
parameter [31:0] MASKED_IRQ = 32'h 0000_0000,
parameter [31:0] LATCHED_IRQ = 32'h ffff_ffff,
parameter [31:0] PROGADDR_RESET = 32'h 0000_0000,
parameter [31:0] PROGADDR_IRQ = 32'h 0000_0010,
parameter [31:0] STACKADDR = 32'h ffff_ffff
) (
output [7:0] trap,
output [31:0] dbg_insn_addr,
output [31:0] dbg_insn_opcode,
// Wishbone interfaces
input wb_rst_i,
input wb_clk_i,
output reg [31:0] wbm_adr_o,
output reg [31:0] wbm_dat_o,
input [31:0] wbm_dat_i,
output reg wbm_we_o,
output reg [3:0] wbm_sel_o,
output reg wbm_stb_o,
input wbm_ack_i,
output reg wbm_cyc_o,
// Pico Co-Processor Interface (PCPI)
output pcpi_valid,
output [31:0] pcpi_insn,
output [31:0] pcpi_rs1,
output [31:0] pcpi_rs2,
input pcpi_wr,
input [31:0] pcpi_rd,
input pcpi_wait,
input pcpi_ready,
// IRQ interface
input [31:0] irq,
output [31:0] eoi,
`ifdef RISCV_FORMAL
output rvfi_valid,
output [63:0] rvfi_order,
output [31:0] rvfi_insn,
output rvfi_trap,
output rvfi_halt,
output rvfi_intr,
output [ 4:0] rvfi_rs1_addr,
output [ 4:0] rvfi_rs2_addr,
output [31:0] rvfi_rs1_rdata,
output [31:0] rvfi_rs2_rdata,
output [ 4:0] rvfi_rd_addr,
output [31:0] rvfi_rd_wdata,
output [31:0] rvfi_pc_rdata,
output [31:0] rvfi_pc_wdata,
output [31:0] rvfi_mem_addr,
output [ 3:0] rvfi_mem_rmask,
output [ 3:0] rvfi_mem_wmask,
output [31:0] rvfi_mem_rdata,
output [31:0] rvfi_mem_wdata,
`endif
// Trace Interface
output trace_valid,
output [35:0] trace_data,
output debug_state,
output mem_instr
);
wire mem_valid;
wire [31:0] mem_addr;
wire [31:0] mem_wdata;
wire [ 3:0] mem_wstrb;
reg mem_ready;
reg [31:0] mem_rdata;
wire clk;
wire resetn;
assign clk = wb_clk_i;
assign resetn = ~wb_rst_i;
picorv32 #(
.ENABLE_COUNTERS (ENABLE_COUNTERS ),
.ENABLE_COUNTERS64 (ENABLE_COUNTERS64 ),
.ENABLE_REGS_16_31 (ENABLE_REGS_16_31 ),
.ENABLE_REGS_DUALPORT(ENABLE_REGS_DUALPORT),
.TWO_STAGE_SHIFT (TWO_STAGE_SHIFT ),
.BARREL_SHIFTER (BARREL_SHIFTER ),
.TWO_CYCLE_COMPARE (TWO_CYCLE_COMPARE ),
.TWO_CYCLE_ALU (TWO_CYCLE_ALU ),
.COMPRESSED_ISA (COMPRESSED_ISA ),
.CATCH_MISALIGN (CATCH_MISALIGN ),
.CATCH_ILLINSN (CATCH_ILLINSN ),
.ENABLE_PCPI (ENABLE_PCPI ),
.ENABLE_MUL (ENABLE_MUL ),
.ENABLE_FAST_MUL (ENABLE_FAST_MUL ),
.ENABLE_DIV (ENABLE_DIV ),
.ENABLE_IRQ (ENABLE_IRQ ),
.ENABLE_IRQ_QREGS (ENABLE_IRQ_QREGS ),
.ENABLE_IRQ_TIMER (ENABLE_IRQ_TIMER ),
.ENABLE_TRACE (ENABLE_TRACE ),
.REGS_INIT_ZERO (REGS_INIT_ZERO ),
.MASKED_IRQ (MASKED_IRQ ),
.LATCHED_IRQ (LATCHED_IRQ ),
.PROGADDR_RESET (PROGADDR_RESET ),
.PROGADDR_IRQ (PROGADDR_IRQ ),
.STACKADDR (STACKADDR )
) picorv32_core (
.clk (clk ),
.resetn (resetn),
.trap (trap ),
.mem_valid(mem_valid),
.mem_addr (mem_addr ),
.mem_wdata(mem_wdata),
.mem_wstrb(mem_wstrb),
.mem_instr(mem_instr),
.mem_ready(mem_ready),
.mem_rdata(mem_rdata),
.pcpi_valid(pcpi_valid),
.pcpi_insn (pcpi_insn ),
.pcpi_rs1 (pcpi_rs1 ),
.pcpi_rs2 (pcpi_rs2 ),
.pcpi_wr (pcpi_wr ),
.pcpi_rd (pcpi_rd ),
.pcpi_wait (pcpi_wait ),
.pcpi_ready(pcpi_ready),
.irq(irq),
.eoi(eoi),
`ifdef RISCV_FORMAL
.rvfi_valid (rvfi_valid ),
.rvfi_order (rvfi_order ),
.rvfi_insn (rvfi_insn ),
.rvfi_trap (rvfi_trap ),
.rvfi_halt (rvfi_halt ),
.rvfi_intr (rvfi_intr ),
.rvfi_rs1_addr (rvfi_rs1_addr ),
.rvfi_rs2_addr (rvfi_rs2_addr ),
.rvfi_rs1_rdata(rvfi_rs1_rdata),
.rvfi_rs2_rdata(rvfi_rs2_rdata),
.rvfi_rd_addr (rvfi_rd_addr ),
.rvfi_rd_wdata (rvfi_rd_wdata ),
.rvfi_pc_rdata (rvfi_pc_rdata ),
.rvfi_pc_wdata (rvfi_pc_wdata ),
.rvfi_mem_addr (rvfi_mem_addr ),
.rvfi_mem_rmask(rvfi_mem_rmask),
.rvfi_mem_wmask(rvfi_mem_wmask),
.rvfi_mem_rdata(rvfi_mem_rdata),
.rvfi_mem_wdata(rvfi_mem_wdata),
`endif
.dbg_insn_addr(dbg_insn_addr),
.dbg_insn_opcode(dbg_insn_opcode),
.trace_valid(trace_valid),
.trace_data (trace_data)
);
localparam IDLE = 2'b00;
localparam WBSTART = 2'b01;
localparam WBEND = 2'b10;
reg [1:0] state;
assign debug_state = state;
wire we;
assign we = (mem_wstrb[0] | mem_wstrb[1] | mem_wstrb[2] | mem_wstrb[3]);
always @(posedge wb_clk_i) begin
if (wb_rst_i) begin
wbm_adr_o <= 0;
wbm_dat_o <= 0;
wbm_we_o <= 0;
wbm_sel_o <= 0;
wbm_stb_o <= 0;
wbm_cyc_o <= 0;
state <= IDLE;
end else begin
case (state)
IDLE: begin
if (mem_valid) begin
wbm_adr_o <= mem_addr;
wbm_dat_o <= mem_wdata;
wbm_we_o <= we;
wbm_sel_o <= mem_wstrb;
wbm_stb_o <= 1'b1;
wbm_cyc_o <= 1'b1;
state <= WBSTART;
end else begin
mem_ready <= 1'b0;
wbm_stb_o <= 1'b0;
wbm_cyc_o <= 1'b0;
wbm_we_o <= 1'b0;
end
end
WBSTART:begin
if (wbm_ack_i) begin
mem_rdata <= wbm_dat_i;
mem_ready <= 1'b1;
state <= WBEND;
wbm_stb_o <= 1'b0;
wbm_cyc_o <= 1'b0;
wbm_we_o <= 1'b0;
end
end
WBEND: begin
mem_ready <= 1'b0;
state <= IDLE;
end
default:
state <= IDLE;
endcase
end
end
endmodule

View File

@ -166,10 +166,12 @@ class UpsilonSoC(SoCCore):
def add_picorv32(self, name, size=0x1000, origin=0x10000, param_origin=0x100000):
pico = PicoRV32(name, origin, origin+0x10)
self.add_module(name, pico)
self.bus.add_slave(name + "_dbg_reg", pico.debug_reg_read.bus,
SoCRegion(origin=None, size=pico.debug_reg_read.width, cached=True))
ram = self.add_blockram(name + "_ram", size=size, connect_now=False)
ram_iface = self.add_preemptive_interface(name + "ram_iface", 2, ram)
pico.add_region("main",
pico.mmap.add_region("main",
BasicRegion(origin=origin, size=size, bus=ram_iface.buses[1]))
self.bus.add_slave(name + "_ram", ram_iface.buses[0],
@ -182,6 +184,14 @@ class UpsilonSoC(SoCCore):
local_ip="192.168.2.50",
remote_ip="192.168.2.100",
tftp_port=6969):
"""
:param variant: Arty A7 variant. Accepts "a7-35" or "a7-100".
:param local_ip: The IP that the BIOS will use when transmitting.
:param remote_ip: The IP that the BIOS will use when retreving
the Linux kernel via TFTP.
:param tftp_port: Port that the BIOS uses for TFTP.
"""
sys_clk_freq = int(100e6)
platform = board_spec.Platform(variant=variant, toolchain="f4pga")
rst = platform.request("cpu_reset")
@ -263,8 +273,8 @@ class UpsilonSoC(SoCCore):
self.add_picorv32("pico0")
def main():
""" Add modifications to SoC variables here """
soc =UpsilonSoC(variant="a7-100")
from config import config
soc =UpsilonSoC(**config)
builder = Builder(soc, csr_json="csr.json", compile_software=True)
builder.build()

View File

@ -16,12 +16,14 @@ class PreemptiveInterface(LiteXModule):
single slave. A master controls which master (or interconnect) has access
to the slave. This is to avoid bus contention by having multiple buses. """
def __init__(self, masters_len, slave):
def __init__(self, masters_len, slave, addressing="word"):
"""
:param masters_len: The amount of buses accessing this slave. This number
must be greater than one.
:param slave: The slave device. This object must have an Interface object
accessable as ``bus``.
:param addressing: Addressing style of the slave. Default is "word". Note
that masters may have to convert when selecting self.buses.
"""
assert masters_len > 1
@ -31,7 +33,7 @@ class PreemptiveInterface(LiteXModule):
for i in range(masters_len):
# Add the slave interface each master interconnect sees.
self.buses.append(Interface(data_width=32, address_width=32, addressing="byte"))
self.buses.append(Interface(data_width=32, address_width=32, addressing=addressing))
"""
Construct a combinatorial case statement. In verilog, the case
@ -109,10 +111,14 @@ class ControlLoopParameters(LiteXModule):
self.zset = CSRStatus(32, description='Set Z position')
self.zpos = CSRStatus(32, description='Measured Z position')
self.bus = Interface(data_width = 32, address_width = 32, addressing="word")
self.bus = Interface(data_width = 32, address_width = 32, addressing="byte")
self.width = 0x20
self.comb += [
self.bus.err.eq(0),
]
self.sync += [
If(self.bus.cyc == 1 and self.bus.stb == 1 and self.bus.ack == 0,
If(self.bus.cyc & self.bus.stb & ~self.bus.ack,
Case(self.bus.adr[0:4], {
0x0: self.bus.dat_r.eq(self.cl_I.storage),
0x4: self.bus.dat_r.eq(self.cl_P.storage),
@ -128,26 +134,59 @@ class ControlLoopParameters(LiteXModule):
).Else(
self.bus.dat_r.eq(self.zpos.status)
),
"default": self.bus.dat_r.eq(0xdeadbeef),
"default": self.bus.dat_r.eq(0xdeadc0de),
}),
self.bus.ack.eq(1),
).Else(
).Elif(self.bus.cyc != 1,
self.bus.ack.eq(0),
)
]
class PicoRV32(LiteXModule, MemoryMap):
class PicoRV32RegisterRead(LiteXModule):
def __init__(self):
self.regs = [Signal(32) for i in range(1,32)]
self.bus = Interface(data_width = 32, address_width = 32, addressing="byte")
self.width = 0x80
cases = {"default": self.bus.dat_r.eq(0xdeaddead)}
for i, reg in enumerate(self.regs):
cases[i*0x4] = self.bus.dat_r.eq(reg)
# self.debug_addr = CSRStatus(32)
# self.debug_cntr = CSRStatus(16)
# CYC -> transfer in progress
# STB -> data is valid on the input lines
self.sync += [
If(self.bus.cyc & self.bus.stb & ~self.bus.ack,
Case(self.bus.adr[0:7], cases),
self.bus.ack.eq(1),
#self.debug_addr.status.eq(self.bus.adr),
#self.debug_cntr.status.eq(self.debug_cntr.status + 1),
).Elif(self.bus.cyc != 1,
self.bus.ack.eq(0)
)
]
# Parts of this class come from LiteX.
#
# Copyright (c) 2016-2019 Florent Kermarrec <florent@enjoy-digital.fr>
# Copyright (c) 2018 Sergiusz Bazanski <q3k@q3k.org>
# Copyright (c) 2019 Antmicro <www.antmicro.com>
# Copyright (c) 2019 Tim 'mithro' Ansell <me@mith.ro>
# Copyright (c) 2018 William D. Jones <thor0505@comcast.net>
# SPDX-License-Identifier: BSD-2-Clause
class PicoRV32(LiteXModule):
def add_params(self, origin):
params = ControlLoopParameters()
self.add_module("params", params)
self.add_region('params', BasicRegion(origin, params.width, params.bus))
self.mmap.add_region('params', BasicRegion(origin, params.width, params.bus))
def __init__(self, name, start_addr=0x10000, irq_addr=0x10010):
MemoryMap.__init__(self)
def __init__(self, name, start_addr=0x10000, irq_addr=0x10010, stackaddr=0x100FF):
self.name = name
self.masterbus = Interface(data_width=32, address_width=32, addressing="byte")
self.mmap = MemoryMap(self.masterbus)
self.resetpin = CSRStorage(1, name="enable", description="PicoRV32 enable")
self.trap = CSRStatus(8, name="trap", description="Trap condition")
@ -156,30 +195,64 @@ class PicoRV32(LiteXModule, MemoryMap):
self.dbg_insn_addr = CSRStatus(32)
self.dbg_insn_opcode = CSRStatus(32)
self.debug_reg_read = PicoRV32RegisterRead()
reg_args = {}
for i in range(1,32):
reg_args[f"o_dbg_reg_x{i}"] = self.debug_reg_read.regs[i-1]
mem_valid = Signal()
mem_instr = Signal()
mem_ready = Signal()
mem_addr = Signal(32)
mem_wdata = Signal(32)
mem_wstrb = Signal(4)
mem_rdata = Signal(32)
self.comb += [
self.d_adr.status.eq(self.masterbus.adr),
self.d_dat_w.status.eq(self.masterbus.dat_w),
self.masterbus.adr.eq(mem_addr),
self.masterbus.dat_w.eq(mem_wdata),
self.masterbus.we.eq(mem_wstrb != 0),
self.masterbus.sel.eq(mem_wstrb),
self.masterbus.cyc.eq(mem_valid),
self.masterbus.stb.eq(mem_valid),
self.masterbus.cti.eq(0),
self.masterbus.bte.eq(0),
mem_ready.eq(self.masterbus.ack),
mem_rdata.eq(self.masterbus.dat_r),
]
self.comb += [
self.d_adr.status.eq(mem_addr),
self.d_dat_w.status.eq(mem_wdata),
]
# NOTE: need to compile to these extact instructions
self.specials += Instance("picorv32_wb",
self.specials += Instance("picorv32",
p_COMPRESSED_ISA = 1,
p_ENABLE_MUL = 1,
p_REGS_INIT_ZERO = 1,
p_PROGADDR_RESET=start_addr,
p_PROGADDR_IRQ =irq_addr,
p_REGS_INIT_ZERO = 1,
p_STACKADDR = stackaddr,
o_trap = self.trap.status,
i_wb_rst_i = ~self.resetpin.storage,
i_wb_clk_i = ClockSignal(),
o_wbm_adr_o = self.masterbus.adr,
o_wbm_dat_o = self.masterbus.dat_w,
i_wbm_dat_i = self.masterbus.dat_r,
o_wbm_we_o = self.masterbus.we,
o_wbm_sel_o = self.masterbus.sel,
o_wbm_stb_o = self.masterbus.stb,
i_wbm_ack_i = self.masterbus.ack,
o_wbm_cyc_o = self.masterbus.cyc,
o_mem_valid = mem_valid,
o_mem_instr = mem_instr,
i_mem_ready = mem_ready,
o_mem_addr = mem_addr,
o_mem_wdata = mem_wdata,
o_mem_wstrb = mem_wstrb,
i_mem_rdata = mem_rdata,
i_clk = ClockSignal(),
i_resetn = self.resetpin.storage,
o_mem_la_read = Signal(),
o_mem_la_write = Signal(),
o_mem_la_addr = Signal(32),
o_mem_la_wdata = Signal(32),
o_mem_la_wstrb = Signal(4),
o_pcpi_valid = Signal(),
o_pcpi_insn = Signal(32),
@ -195,12 +268,13 @@ class PicoRV32(LiteXModule, MemoryMap):
o_trace_valid = Signal(),
o_trace_data = Signal(36),
o_debug_state = Signal(2),
o_dbg_insn_addr = self.dbg_insn_addr.status,
o_dbg_insn_opcode = self.dbg_insn_opcode.status,
**reg_args
)
def do_finalize(self):
self.dump_mmap(self.name + ".json")
self.submodules.decoder = self.bus_submodule(self.masterbus)
self.mmap.dump_mmap(self.name + ".json")
self.mmap.finalize()

View File

@ -1,4 +1,4 @@
test.bin: test.elf
riscv64-unknown-elf-objcopy -O binary -j .text test.elf test.bin
test.elf: test.c
riscv64-unknown-elf-gcc -march=rv32imc -mabi=ilp32 -ffreestanding -nostdlib -Os -Wl,-build-id=none,-Bstatic,-T,riscv.ld,--strip-debug -nostartfiles -lgcc test.c -o test.elf
riscv64-unknown-elf-gcc -march=rv32im -mabi=ilp32 -ffreestanding -nostdlib -Os -Wl,-build-id=none,-Bstatic,-T,riscv.ld,--strip-debug -nostartfiles -lgcc test.c -o test.elf

View File

@ -5,13 +5,19 @@ def read_file(filename):
with open(filename, 'rb') as f:
return f.read()
def u(n):
return hex(n & 0xFFFFFFFF)
def check_running():
print("Running:", machine.mem32[pico0_enable])
print("Trap status:", machine.mem32[pico0_trap])
print("Bus address:", hex(machine.mem32[pico0_d_adr]))
print("Bus write value:", hex(machine.mem32[pico0_d_dat_w]))
print("Instruction address:", hex(machine.mem32[pico0_dbg_insn_addr]))
print("Opcode:", hex(machine.mem32[pico0_dbg_insn_opcode]))
print("Bus address:", u(machine.mem32[pico0_d_adr]))
print("Bus write value:", u(machine.mem32[pico0_d_dat_w]))
print("Instruction address:", u(machine.mem32[pico0_dbg_insn_addr]))
print("Opcode:", u(machine.mem32[pico0_dbg_insn_opcode]))
for num in range(0,31):
print("Register", num + 1, u(machine.mem32[pico0_dbg_reg + num*0x4]))
def run_program(prog, cl_I):
# Reset PicoRV32

View File

@ -4,9 +4,7 @@ void _start(void)
{
volatile uint32_t *write = (volatile uint32_t *)(0x100000 + 0x10);
volatile uint32_t *read = (volatile uint32_t *)( 0x100000 + 0x0);
volatile uint32_t *next_read = (volatile uint32_t *)(0x100FF);
*write = *read;
*next_read = 0xdeadbeef;
for (;;) ;
}