[dv] Add co-simulation environment support to UVM testbench

This commit is contained in:
Greg Chadwick 2021-09-17 15:49:06 +01:00 committed by Greg Chadwick
parent c03cc91a5d
commit 416ecb10df
30 changed files with 928 additions and 65 deletions

153
doc/03_reference/cosim.rst Normal file
View file

@ -0,0 +1,153 @@
.. _cosim:
Co-simulation System
====================
Overview
--------
The Ibex UVM DV environment contains a co-simulation system.
This system runs a RISC-V ISS (currently only Spike is supported) in lockstep with an Ibex core.
All instructions executed by Ibex and memory transactions generated are checked against the behaviour of the ISS.
This system supports memory errors, interrupt and debug requests which are observed in the RTL simulation and forwarded to the ISS so the ISS and RTL remain in sync.
The system uses a generic interface to allow support of multiple ISSes.
Only VCS is supported as a simulator, though no VCS specific functionality is required so adding support for another simulator should be straight-forward.
To run the co-simulation system the `ibex-cosim branch from the lowRISC fork of Spike <https://github.com/lowRISC/riscv-isa-sim/tree/ibex>`_ is required.
The RISC-V Formal Interface (RVFI) is used to provide information about retired instructions and instructions that produce synchronous traps for checking.
The RVFI has been extended to provide interrupt and debug information and the value of the ``mcycle`` CSR.
These extended signals have the prefix ``rvfi_ext``
The co-simulation system is EXPERIMENTAL.
It is disabled by default in the UVM DV environment currently, however it is intended to become the primary checking method for the UVM testbench.
Setup and Usage
---------------
Clone the `lowRISC fork of Spike <https://github.com/lowRISC/riscv-isa-sim>`_ and checkout the ``ibex_cosim`` branch.
Follow the Spike build instructions to build and install Spike.
The build will install multiple header files and libraries, it is recommended a custom install location (using ``--prefix=<path>`` with ``configure``) is used to avoid cluttering system directories.
The ``--enable-commitlog`` and ``--enable-misaligned`` options must be passed to ``configure``.
Once built, the ``IBEX_COSIM_ISS_ROOT`` environment variable must be set to the Spike root install directory (as given by ``--prefix=<path>`` to ``configure``) in order to build the UVM DV environment with co-simulation support.
To build/run the UVM DV environment with the co-simulator add the ``COSIM=1`` argument to the make command.
Quick Build and Run Instructions
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
.. code-block:: bash
# Get the Ibex co-simulation spike branch
git clone -b ibex_cosim https://github.com/lowRISC/riscv-isa-sim.git riscv-isa-sim-cosim
# Setup build directory
cd riscv-isa-sim-cosim
mkdir build
cd build
# Configure and build spike
../configure --enable-commitlog --enable-misaligned --prefix=/tools/spike-ibex-cosim
make -j8 install
# Setup IBEX_COSIM_ISS_ROOT to allow DV flow to use co-simulation
export IBEX_COSIM_ISS_ROOT=/tools/spike-ibex-cosim
# Run regression with co-simulation enabled
cd <ibex_area>/dv/uvm/core_ibex
make COSIM=1
Co-simulation details
----------------------
The co-simulation system uses DPI calls to link the DV and ISS sides together.
A C++ interface is defined in ``dv/cosim/cosim.h`` with a DPI wrapper provided by ``dv/cosim/cosim_dpi.cc`` and ``dv/cosim/cosim_dpi.h``.
A ``chandle``, which points to some class instance that implements the interface, must be provided by the DV environment.
All the co-simulation DPI calls take this ``chandle`` as a first argument.
The details below discuss the C++ interface.
The DPI version of the interface is almost identical, with all functions prefaced with ``riscv_cosim`` and taking a ``chandle`` of the co-simulation instance to use.
The core function of the co-simulation interface is the ``step`` function:
.. code-block:: c++
virtual bool step(uint32_t write_reg, uint32_t write_reg_data, uint32_t pc, bool sync_trap);
``step`` takes arguments giving the PC of the most recently retired or synchronously trapping instruction in the DUT along with details of any register write that occurred.
Where ``step`` is provided with a retired (successfully executed) instruction it steps the ISS by one instruction and checks it executed the same instruction, with the same register write result, as the DUT.
When ``step`` is provided with an instruction that produces a synchronous trap, it checks the ISS also traps on the same instruction but does not step to the next executed instruction.
That instruction will be the first instruction of the trap handler and will be checked/stepped by the next call to ``step`` when it retires from the DUT.
Any data memory accesses that the ISS produces during the ``step`` are checked against observed DUT memory accesses.
``step`` returns false if any checks have failed.
If any errors occur during the step they can be accessed via ``get_errors`` which returns a vector of error messages.
For the DPI interface errors are accessed using ``riscv_cosim_get_num_errors`` and ``riscv_cosim_get_error``.
When errors have been checked they can be cleared with ``clear_errors``.
Trap Handling
^^^^^^^^^^^^^
Traps are separated into two categories, synchronous and asynchronous.
Synchronous traps are caused by a particular instruction's execution (e.g. an illegal instruction).
Asynchronous traps are caused by external interrupts.
Note that in Ibex error responses to both loads and store produce a synchronous trap so the co-simulation system has the same behaviour.
A synchronous trap is associated with a particular instruction and prevents that instruction from completing its execution.
That instruction doesn't retire, but is still made visible on the RVFI.
The ``rvfi_trap`` signal is asserted for an instruction that causes a synchronous trap.
As described above ``step`` should be called for any instruction that causes a synchronous trap to check the trap is also seen by the ISS.
An asynchronous trap can be seen as occurring between instructions and as such doesn't have an associated instruction, nothing will be seen on RVFI with ``rvfi_trap`` set.
The co-simulation system will immediately take any pending asynchronous trap when ``step`` is called, expecting the instruction checked with ``step`` to be the first instruction of the trap handler.
While a debug request is not strictly an asynchronous trap (it doesn't use the same exception handling mechanism), they work identically to asynchronous traps for the co-simulation system.
When a debug request is pending when ``step`` is called the co-simulation will expect the instruction checked by ``step`` to be the first instruction of the debug handler.
Interrupts and Debug Requests
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
The DV environment must observe any incoming interrupts and debug requests generated by the testbench and notify the co-simulation system of them using ``set_mip``, ``set_debug_req`` and ``set_nmi``.
An interrupt or debug request will take immediate effect at the next ``step`` (if architecturally required to do so).
The DV environment is responsible for determining when to call ``set_mip``, ``set_debug_req`` and ``set_nmi`` to ensure a RTL and co-simulation match.
The state of the incoming interrupts and debug request is sampled when an instruction moves from IF to ID/EX.
The sampled state is tracked with the rest of the RVFI pipeline and used to call ``set_mip``, ``set_debug_req`` and ``set_nmi`` when the instruction is output by the RVFI.
See the comments in :file:`rtl/ibex_core.sv`, around the ``new_debug_req``, ``new_nmi`` and ``new_irq`` signals for further details.
Memory Access Checking and Bus Errors
^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^
The co-simulation system must be informed of all Dside accesses performed by the RTL using ``notify_dside_access``.
See :file:`dv/cosim/cosim.h` for further details.
As Ibex doesn't perform speculative Dside memory accesses, all notified accesses are expected to match with accesses performed by the ISS in the same order they are notified.
Accesses notified via ``notify_dside_access`` can specify they saw an error response, the co-simulation system will produce the appropriate trap when the ISS attempts to access the address that saw the error.
Accesses must be notified before they occur in the ISS for the access matching and trapping on errors to work.
Iside accesses from Ibex can be speculative, so there is no simple link between accesses produced by the RTL and the accesses performed by the ISS for the Iside.
This means no direct checking of Iside accesses is done, however errors on the Iside accesses that result in an instruction fault trap need to be notified to the co-simulation system.
``set_iside_error`` does this, it is provided with the address that saw the bus error and it should be called immediately before the ``step`` that will process the trap.
The co-simulation system will produce an instruction fault trap if it attempts to access the provided error address in the ``step`` call following the ``set_iside_error`` call.
Two methods are available for dealing with bus errors on the Iside, they differ in where they probe.
One probes on the external instr_X memory interface, the other probes internally within the IF stage.
The probe used is selected by the ``probe_imem_for_err`` field of the ``core_ibex_cosim_cfg`` structure.
When set external probing is used, otherwise internal probing is used.
Both probe points look for addresses that have seen bus errors.
If an instruction entering ID/EX fetches from an address that has seen a bus error (as recorded by one of the probing methods) its ``rvfi_order_id`` is recorded.
When a faulting instruction is reported on the RVFI and its ``rvfi_order_id`` matches a recorded faulting one ``set_iside_error`` is called with the faulting address before the next ``step``.
The external interface probe should be used when it is guaranteed that a bus error to address A on the external interface results in a fetch error the next time an instruction with address A is observed entering the ID/EX stage (providing no successful access to A has occurred in the mean time).
Otherwise the internal probe should be used.
When Ibex is used with the prefetch buffer this guarantee holds and the external probe can be used.
When Ibex is used with the instruction cache this guarantee does not hold and the internal probe must be used.
Care should be taken when using the internal probe as it will miss any bug that causes instruction faults to be ignored by the prefetch buffer or ICache (or whatever else has been used in place of these by a custom implementation).
In the case of the Ibex ICache a separate testbench ensures instruction faults are dealt with appropriately within the ICache.

View file

@ -22,5 +22,6 @@ It describes the design in detail, discusses the verification approach and the r
debug
tracer
verification
cosim
rvfi
history

View file

@ -4,6 +4,17 @@
GEN_DIR := $(realpath ../../../vendor/google_riscv-dv)
TOOLCHAIN := ${RISCV_TOOLCHAIN}
export IBEX_ROOT := $(realpath ../../../)
ifeq ($(COSIM),1)
ifndef IBEX_COSIM_ISS_ROOT
$(error IBEX_COSIM_ISS_ROOT must be set to the root of a suitable spike build if COSIM=1)
else
# Spike builds a libsoftfloat.so shared library that the simulator binary needs.
# Set LD_LIBRARY_PATH so it can be found.
export LD_LIBRARY_PATH := $(IBEX_COSIM_ISS_ROOT)/lib/:${LD_LIBRARY_PATH}
endif
endif
# Explicitly ask for the bash shell
SHELL := bash
@ -349,7 +360,7 @@ all-verilog = \
$(shell find ../../../rtl -name '*.v' -o -name '*.sv' -o -name '*.svh') \
$(shell find ../.. -name '*.v' -o -name '*.sv' -o -name '*.svh')
compile-var-deps := COMMON_OPTS SIMULATOR COV WAVES COMPILE_OPTS
compile-var-deps := COMMON_OPTS SIMULATOR COV WAVES COMPILE_OPTS COSIM
-include $(OUT-DIR)rtl_sim/.compile-vars.mk
compile-vars-prereq = $(call vars-prereq,comp,compiling TB,$(compile-var-deps))
@ -357,6 +368,7 @@ $(call dump-vars-match,$(compile-var-deps),comp)
cov-arg := $(if $(call equal,$(COV),1),--en_cov,)
wave-arg := $(if $(call equal,$(WAVES),1),--en_wave,)
cosim-arg := $(if $(call equal,$(COSIM),1),--en_cosim,)
lsf-arg := $(if $(LSF_CMD),--lsf_cmd="$(LSF_CMD)",)
$(OUT-DIR)rtl_sim/.compile.stamp: \
@ -368,7 +380,7 @@ $(OUT-DIR)rtl_sim/.compile.stamp: \
--steps=compile \
${COMMON_OPTS} \
--simulator="${SIMULATOR}" --simulator_yaml=yaml/rtl_simulation.yaml \
$(cov-arg) $(wave-arg) $(lsf-arg) \
$(cov-arg) $(wave-arg) $(cosim-arg) $(lsf-arg) \
--cmp_opts="${COMPILE_OPTS}"
$(call dump-vars,$(OUT-DIR)rtl_sim/.compile-vars.mk,comp,$(compile-var-deps))
@touch $@

View file

@ -0,0 +1,24 @@
interface core_ibex_ifetch_if(input logic clk);
logic reset;
logic fetch_ready;
logic fetch_valid;
logic [31:0] fetch_rdata;
logic [31:0] fetch_addr;
logic fetch_err;
logic fetch_err_plus2;
clocking monitor_cb @(posedge clk);
input reset;
input fetch_ready;
input fetch_valid;
input fetch_rdata;
input fetch_addr;
input fetch_err;
input fetch_err_plus2;
endclocking
task automatic wait_clks(input int num);
repeat (num) @(posedge clk);
endtask
endinterface

View file

@ -0,0 +1,44 @@
// Copyright lowRISC contributors.
// Licensed under the Apache License, Version 2.0, see LICENSE for details.
// SPDX-License-Identifier: Apache-2.0
`include "cosim_dpi.svh"
class ibex_cosim_agent extends uvm_agent;
ibex_rvfi_monitor rvfi_monitor;
ibex_ifetch_monitor ifetch_monitor;
ibex_cosim_scoreboard scoreboard;
uvm_analysis_export#(ibex_mem_intf_seq_item) dmem_port;
uvm_analysis_export#(ibex_mem_intf_seq_item) imem_port;
`uvm_component_utils(ibex_cosim_agent)
function new(string name="", uvm_component parent=null);
super.new(name, parent);
dmem_port = new("dmem_port", this);
imem_port = new("imem_port", this);
endfunction
virtual function void build_phase(uvm_phase phase);
super.build_phase(phase);
rvfi_monitor = ibex_rvfi_monitor::type_id::create("rvfi_monitor", this);
scoreboard = ibex_cosim_scoreboard::type_id::create("scoreboard", this);
ifetch_monitor = ibex_ifetch_monitor::type_id::create("ifetch_monitor", this);
endfunction: build_phase
virtual function void connect_phase(uvm_phase phase);
super.connect_phase(phase);
rvfi_monitor.item_collected_port.connect(scoreboard.rvfi_port.analysis_export);
ifetch_monitor.item_collected_port.connect(scoreboard.ifetch_port.analysis_export);
dmem_port.connect(scoreboard.dmem_port.analysis_export);
imem_port.connect(scoreboard.imem_port.analysis_export);
endfunction: connect_phase
function void write_mem_byte(bit [31:0] addr, bit [7:0] d);
riscv_cosim_write_mem_byte(scoreboard.cosim_handle, addr, d);
endfunction
endclass : ibex_cosim_agent

View file

@ -0,0 +1,20 @@
// Copyright lowRISC contributors.
// Licensed under the Apache License, Version 2.0, see LICENSE for details.
// SPDX-License-Identifier: Apache-2.0
package ibex_cosim_agent_pkg;
`ifdef INC_IBEX_COSIM
import uvm_pkg::*;
import ibex_mem_intf_agent_pkg::*;
`include "uvm_macros.svh"
`include "ibex_cosim_cfg.sv"
`include "ibex_rvfi_seq_item.sv"
`include "ibex_rvfi_monitor.sv"
`include "ibex_ifetch_seq_item.sv"
`include "ibex_ifetch_monitor.sv"
`include "ibex_cosim_scoreboard.sv"
`include "ibex_cosim_agent.sv"
`endif
endpackage

View file

@ -0,0 +1,19 @@
// Copyright lowRISC contributors.
// Licensed under the Apache License, Version 2.0, see LICENSE for details.
// SPDX-License-Identifier: Apache-2.0
class core_ibex_cosim_cfg extends uvm_object;
bit [31:0] start_pc;
bit [31:0] start_mtvec;
bit probe_imem_for_errs;
string log_file;
`uvm_object_utils_begin(core_ibex_cosim_cfg)
`uvm_field_int(start_pc, UVM_DEFAULT)
`uvm_field_int(start_mtvec, UVM_DEFAULT)
`uvm_field_int(probe_imem_for_errs, UVM_DEFAULT)
`uvm_field_string(log_file, UVM_DEFAULT)
`uvm_object_utils_end
`uvm_object_new
endclass

View file

@ -0,0 +1,240 @@
// Copyright lowRISC contributors.
// Licensed under the Apache License, Version 2.0, see LICENSE for details.
// SPDX-License-Identifier: Apache-2.0
`include "spike_cosim_dpi.svh"
`include "cosim_dpi.svh"
class ibex_cosim_scoreboard extends uvm_scoreboard;
chandle cosim_handle;
core_ibex_cosim_cfg cfg;
uvm_tlm_analysis_fifo #(ibex_rvfi_seq_item) rvfi_port;
uvm_tlm_analysis_fifo #(ibex_mem_intf_seq_item) dmem_port;
uvm_tlm_analysis_fifo #(ibex_mem_intf_seq_item) imem_port;
uvm_tlm_analysis_fifo #(ibex_ifetch_seq_item) ifetch_port;
virtual core_ibex_instr_monitor_if instr_vif;
bit failed_iside_accesses [bit[31:0]];
typedef struct {
bit [63:0] order;
bit [31:0] addr;
} iside_err_t;
iside_err_t iside_error_queue [$];
`uvm_component_utils(ibex_cosim_scoreboard)
function new(string name="", uvm_component parent=null);
super.new(name, parent);
rvfi_port = new("rvfi_port", this);
dmem_port = new("dmem_port", this);
imem_port = new("imem_port", this);
ifetch_port = new("ifetch_port", this);
cosim_handle = null;
endfunction
function void build_phase(uvm_phase phase);
super.build_phase(phase);
if (!uvm_config_db#(core_ibex_cosim_cfg)::get(this, "", "cosim_cfg", cfg)) begin
`uvm_fatal(`gfn, "Cannot get cosim configuration")
end
if (!uvm_config_db#(virtual core_ibex_instr_monitor_if)::get(null, "", "instr_monitor_if",
instr_vif)) begin
`uvm_fatal(`gfn, "Cannot get instr_monitor_if")
end
// TODO: Ensure log file on reset gets append rather than overwrite?
cosim_handle = spike_cosim_init(cfg.start_pc, cfg.start_mtvec, cfg.log_file);
if (cosim_handle == null) begin
`uvm_fatal(`gfn, "Could not initialise cosim")
end
endfunction : build_phase
virtual task run_phase(uvm_phase phase);
wait (instr_vif.instr_cb.reset === 1'b0);
forever begin
fork begin: isolation_fork
fork
run_cosim_rvfi();
run_cosim_dmem();
run_cosim_imem_errors();
if (cfg.probe_imem_for_errs) begin
run_cosim_imem();
end else begin
run_cosim_ifetch();
end
wait (instr_vif.instr_cb.reset === 1'b1);
join_any
disable fork;
end join
if (instr_vif.instr_cb.reset === 1'b1) handle_reset();
end
endtask : run_phase
task run_cosim_rvfi();
ibex_rvfi_seq_item rvfi_instr;
forever begin
rvfi_port.get(rvfi_instr);
// Remove entries from iside_error_queue where the instruction never reaches the RVFI
// interface because it was flushed.
while (iside_error_queue.size() > 0 && iside_error_queue[0].order < rvfi_instr.order) begin
iside_error_queue.pop_front();
end
// Check if the top of the iside_error_queue relates to the current RVFI instruction. If so
// notify the cosim environment of an instruction error.
if (iside_error_queue.size() !=0 && iside_error_queue[0].order == rvfi_instr.order) begin
riscv_cosim_set_iside_error(cosim_handle, iside_error_queue[0].addr);
iside_error_queue.pop_front();
end
riscv_cosim_set_nmi(cosim_handle, rvfi_instr.nmi);
riscv_cosim_set_mip(cosim_handle, rvfi_instr.mip);
riscv_cosim_set_debug_req(cosim_handle, rvfi_instr.debug_req);
riscv_cosim_set_mcycle(cosim_handle, rvfi_instr.mcycle);
if (!riscv_cosim_step(cosim_handle, rvfi_instr.rd_addr, rvfi_instr.rd_wdata, rvfi_instr.pc,
rvfi_instr.trap)) begin
// cosim instruction step doesn't match rvfi captured instruction, report a fatal error
// with the details
`uvm_fatal(`gfn, get_cosim_error_str())
end
end
endtask: run_cosim_rvfi
task run_cosim_dmem();
ibex_mem_intf_seq_item mem_op;
forever begin
dmem_port.get(mem_op);
// Notify the cosim of all dside accesses emitted by the RTL
riscv_cosim_notify_dside_access(cosim_handle, mem_op.read_write == WRITE, mem_op.addr,
mem_op.data, mem_op.be, mem_op.error, mem_op.misaligned_first, mem_op.misaligned_second);
end
endtask: run_cosim_dmem
task run_cosim_imem();
ibex_mem_intf_seq_item mem_op;
forever begin
// Take stream of transaction from imem monitor. Where an imem access has an error record it
// in failed_iside_accesses. If an access has succeeded remove it from failed_imem_accesses if
// it's there.
// Note all transactions are 32-bit aligned.
imem_port.get(mem_op);
if (mem_op.error) begin
failed_iside_accesses[mem_op.addr] = 1'b1;
end else begin
if (failed_iside_accesses.exists(mem_op.addr)) begin
failed_iside_accesses.delete(mem_op.addr);
end
end
end
endtask: run_cosim_imem
task run_cosim_ifetch();
ibex_ifetch_seq_item ifetch;
bit [31:0] aligned_fetch_addr;
bit [31:0] aligned_fetch_addr_next;
forever begin
ifetch_port.get(ifetch);
aligned_fetch_addr = {ifetch.fetch_addr[31:2], 2'b0};
aligned_fetch_addr_next = aligned_fetch_addr + 32'd4;
if (ifetch.fetch_err) begin
// Instruction error observed in fetch stage
bit [31:0] failing_addr;
// Determine which address failed.
if (ifetch.fetch_err_plus2) begin
// Instruction crosses a 32-bit boundary and second half failed
failing_addr = aligned_fetch_addr_next;
end else begin
failing_addr = aligned_fetch_addr;
end
failed_iside_accesses[failing_addr] = 1'b1;
end else begin
if (ifetch.fetch_addr[1:0] != 0 && ifetch.fetch_rdata[1:0] == 2'b11) begin
// Instruction crosses 32-bit boundary, so remove any failed accesses on the other side of
// the 32-bit boundary.
if (failed_iside_accesses.exists(aligned_fetch_addr_next)) begin
failed_iside_accesses.delete(aligned_fetch_addr_next);
end
end
if (failed_iside_accesses.exists(aligned_fetch_addr)) begin
failed_iside_accesses.delete(aligned_fetch_addr);
end
end
end
endtask: run_cosim_ifetch
task run_cosim_imem_errors();
bit [63:0] latest_order = 64'hffffffff_ffffffff;
bit [31:0] aligned_addr;
forever begin
// Wait for new instruction to appear in ID stage
wait (instr_vif.instr_cb.valid_id &&
instr_vif.instr_cb.instr_new_id &&
latest_order != instr_vif.instr_cb.rvfi_order_id);
// Determine if instruction comes from an address that has seen an error. If an error was seen
// add the instruction order ID and address to iside_error_queue
aligned_addr = instr_vif.instr_cb.pc_id & 32'hfffffffc;
if (failed_iside_accesses.exists(instr_vif.instr_cb.pc_id & 32'hfffffffc)) begin
iside_error_queue.push_back('{order : instr_vif.instr_cb.rvfi_order_id,
addr : instr_vif.instr_cb.pc_id & 32'hfffffffc});
end else if (!instr_vif.instr_cb.is_compressed_id &&
(instr_vif.instr_cb.pc_id & 32'h3) != 0 &&
failed_iside_accesses.exists((instr_vif.instr_cb.pc_id + 32'd4) & 32'hfffffffc))
begin
// Where an instruction crosses a 32-bit boundary, check if an error was seen on the other
// side of the boundary
iside_error_queue.push_back('{order : instr_vif.instr_cb.rvfi_order_id,
addr : (instr_vif.instr_cb.pc_id + 32'd4) & 32'hfffffffc});
end
latest_order = instr_vif.instr_cb.rvfi_order_id;
end
endtask: run_cosim_imem_errors;
function string get_cosim_error_str();
string error = "Cosim mismatch ";
for (int i = 0; i < riscv_cosim_get_num_errors(cosim_handle); ++i) begin
error = {error, riscv_cosim_get_error(cosim_handle, i), "\n"};
end
riscv_cosim_clear_errors(cosim_handle);
return error;
endfunction : get_cosim_error_str
function void final_phase(uvm_phase phase);
super.final_phase(phase);
if (cosim_handle) begin
spike_cosim_release(cosim_handle);
end
endfunction : final_phase
task handle_reset();
if (cosim_handle) begin
spike_cosim_release(cosim_handle);
end
cosim_handle = spike_cosim_init(cfg.start_pc, cfg.start_mtvec, cfg.log_file);
wait (instr_vif.instr_cb.reset === 1'b0);
endtask
endclass : ibex_cosim_scoreboard

View file

@ -0,0 +1,45 @@
// Copyright lowRISC contributors.
// Licensed under the Apache License, Version 2.0, see LICENSE for details.
// SPDX-License-Identifier: Apache-2.0
class ibex_ifetch_monitor extends uvm_monitor;
protected virtual core_ibex_ifetch_if vif;
uvm_analysis_port#(ibex_ifetch_seq_item) item_collected_port;
`uvm_component_utils(ibex_ifetch_monitor)
`uvm_component_new
function void build_phase(uvm_phase phase);
super.build_phase(phase);
item_collected_port = new("item_collected_port", this);
if(!uvm_config_db#(virtual core_ibex_ifetch_if)::get(this, "", "ifetch_if", vif)) begin
`uvm_fatal("NOVIF", {"virtual interface must be set for: ", get_full_name(), ".vif"});
end
endfunction
virtual task run_phase(uvm_phase phase);
ibex_ifetch_seq_item trans_collected;
wait (vif.monitor_cb.reset === 1'b0);
forever begin
while(!(vif.monitor_cb.fetch_valid && vif.monitor_cb.fetch_ready)) vif.wait_clks(1);
trans_collected = ibex_ifetch_seq_item::type_id::create("trans_collected");
trans_collected.fetch_rdata = vif.monitor_cb.fetch_rdata;
trans_collected.fetch_addr = vif.monitor_cb.fetch_addr;
trans_collected.fetch_err = vif.monitor_cb.fetch_err;
trans_collected.fetch_err_plus2 = vif.monitor_cb.fetch_err_plus2;
`uvm_info(`gfn, $sformatf("Seen ifetch:\n%s", trans_collected.sprint()),
UVM_HIGH)
item_collected_port.write(trans_collected);
vif.wait_clks(1);
end
endtask: run_phase
endclass : ibex_ifetch_monitor

View file

@ -0,0 +1,19 @@
// Copyright lowRISC contributors.
// Licensed under the Apache License, Version 2.0, see LICENSE for details.
// SPDX-License-Identifier: Apache-2.0
class ibex_ifetch_seq_item extends uvm_sequence_item;
bit [31:0] fetch_rdata;
bit [31:0] fetch_addr;
bit fetch_err;
bit fetch_err_plus2;
`uvm_object_utils_begin(ibex_ifetch_seq_item)
`uvm_field_int (fetch_rdata, UVM_DEFAULT)
`uvm_field_int (fetch_addr, UVM_DEFAULT)
`uvm_field_int (fetch_err, UVM_DEFAULT)
`uvm_field_int (fetch_err_plus2, UVM_DEFAULT)
`uvm_object_utils_end
`uvm_object_new
endclass : ibex_ifetch_seq_item

View file

@ -0,0 +1,52 @@
// Copyright lowRISC contributors.
// Licensed under the Apache License, Version 2.0, see LICENSE for details.
// SPDX-License-Identifier: Apache-2.0
class ibex_rvfi_monitor extends uvm_monitor;
protected virtual core_ibex_rvfi_if vif;
uvm_analysis_port#(ibex_rvfi_seq_item) item_collected_port;
`uvm_component_utils(ibex_rvfi_monitor)
`uvm_component_new
function void build_phase(uvm_phase phase);
super.build_phase(phase);
item_collected_port = new("item_collected_port", this);
if(!uvm_config_db#(virtual core_ibex_rvfi_if)::get(this, "", "rvfi_if", vif)) begin
`uvm_fatal("NOVIF", {"virtual interface must be set for: ", get_full_name(), ".vif"});
end
endfunction: build_phase
virtual task run_phase(uvm_phase phase);
ibex_rvfi_seq_item trans_collected;
wait (vif.monitor_cb.reset === 1'b0);
forever begin
// Wait for a retired instruction
while(!vif.monitor_cb.valid) vif.wait_clks(1);
// Read instruction details from RVFI interface
trans_collected = ibex_rvfi_seq_item::type_id::create("trans_collected");
trans_collected.trap = vif.monitor_cb.trap;
trans_collected.pc = vif.monitor_cb.pc_rdata;
trans_collected.rd_addr = vif.monitor_cb.rd_addr;
trans_collected.rd_wdata = vif.monitor_cb.rd_wdata;
trans_collected.order = vif.monitor_cb.order;
trans_collected.mip = vif.monitor_cb.ext_mip;
trans_collected.nmi = vif.monitor_cb.ext_nmi;
trans_collected.debug_req = vif.monitor_cb.ext_debug_req;
trans_collected.mcycle = vif.monitor_cb.ext_mcycle;
`uvm_info(get_full_name(), $sformatf("Seen instruction:\n%s", trans_collected.sprint()),
UVM_HIGH)
item_collected_port.write(trans_collected);
vif.wait_clks(1);
end
endtask : run_phase
endclass : ibex_rvfi_monitor

View file

@ -0,0 +1,30 @@
// Copyright lowRISC contributors.
// Licensed under the Apache License, Version 2.0, see LICENSE for details.
// SPDX-License-Identifier: Apache-2.0
class ibex_rvfi_seq_item extends uvm_sequence_item;
bit trap;
bit [31:0] pc;
bit [4:0] rd_addr;
bit [31:0] rd_wdata;
bit [63:0] order;
bit [31:0] mip;
bit nmi;
bit debug_req;
bit [63:0] mcycle;
`uvm_object_utils_begin(ibex_rvfi_seq_item)
`uvm_field_int (trap, UVM_DEFAULT)
`uvm_field_int (pc, UVM_DEFAULT)
`uvm_field_int (rd_addr, UVM_DEFAULT)
`uvm_field_int (rd_wdata, UVM_DEFAULT)
`uvm_field_int (order, UVM_DEFAULT)
`uvm_field_int (mip, UVM_DEFAULT)
`uvm_field_int (nmi, UVM_DEFAULT)
`uvm_field_int (debug_req, UVM_DEFAULT)
`uvm_field_int (mcycle, UVM_DEFAULT)
`uvm_object_utils_end
`uvm_object_new
endclass : ibex_rvfi_seq_item

View file

@ -0,0 +1,30 @@
// Copyright lowRISC contributors.
// Licensed under the Apache License, Version 2.0, see LICENSE for details.
// SPDX-License-Identifier: Apache-2.0
#include <svdpi.h>
#include "cosim.h"
#include "spike_cosim.h"
extern "C" {
void *spike_cosim_init(svBitVecVal *start_pc, svBitVecVal *start_mtvec,
const char *log_file_path_cstr) {
std::string log_file_path;
if (log_file_path_cstr) {
log_file_path = log_file_path_cstr;
}
SpikeCosim *cosim =
new SpikeCosim(start_pc[0], start_mtvec[0], log_file_path, false, true);
cosim->add_memory(0x80000000, 0x10000000);
return static_cast<Cosim *>(cosim);
}
void spike_cosim_release(void *cosim_handle) {
auto cosim = static_cast<Cosim *>(cosim_handle);
delete cosim;
}
}

View file

@ -0,0 +1,7 @@
// Copyright lowRISC contributors.
// Licensed under the Apache License, Version 2.0, see LICENSE for details.
// SPDX-License-Identifier: Apache-2.0
import "DPI-C" function chandle spike_cosim_init(bit [31:0] start_pc, bit [31:0] start_mtvec,
string log_file_path);
import "DPI-C" function void spike_cosim_release(chandle cosim_handle);

View file

@ -22,6 +22,8 @@ interface ibex_mem_intf#(
wire [DATA_WIDTH-1:0] rdata;
wire [INTG_WIDTH-1:0] rintg;
wire error;
wire misaligned_first;
wire misaligned_second;
clocking request_driver_cb @(posedge clk);
input reset;
@ -66,6 +68,8 @@ interface ibex_mem_intf#(
input rdata;
input rintg;
input error;
input misaligned_first;
input misaligned_second;
endclocking
task automatic wait_clks(input int num);

View file

@ -55,6 +55,8 @@ class ibex_mem_intf_monitor extends uvm_monitor;
while(!(vif.monitor_cb.request && vif.monitor_cb.grant)) vif.wait_clks(1);
trans_collected.addr = vif.monitor_cb.addr;
trans_collected.be = vif.monitor_cb.be;
trans_collected.misaligned_first = vif.monitor_cb.misaligned_first;
trans_collected.misaligned_second = vif.monitor_cb.misaligned_second;
`uvm_info(get_full_name(), $sformatf("Detect request with address: %0x",
trans_collected.addr), UVM_HIGH)
if(vif.monitor_cb.we) begin

View file

@ -17,6 +17,8 @@ class ibex_mem_intf_seq_item extends uvm_sequence_item;
rand bit [3:0] req_delay;
rand bit [5:0] rvalid_delay;
rand bit error;
bit misaligned_first;
bit misaligned_second;
`uvm_object_utils_begin(ibex_mem_intf_seq_item)
`uvm_field_int (addr, UVM_DEFAULT)
@ -27,6 +29,8 @@ class ibex_mem_intf_seq_item extends uvm_sequence_item;
`uvm_field_int (gnt_delay, UVM_DEFAULT)
`uvm_field_int (rvalid_delay, UVM_DEFAULT)
`uvm_field_int (error, UVM_DEFAULT)
`uvm_field_int (misaligned_first, UVM_DEFAULT)
`uvm_field_int (misaligned_second, UVM_DEFAULT)
`uvm_object_utils_end
`uvm_object_new

View file

@ -10,6 +10,9 @@ class core_ibex_env extends uvm_env;
ibex_mem_intf_response_agent data_if_response_agent;
ibex_mem_intf_response_agent instr_if_response_agent;
irq_request_agent irq_agent;
`ifdef INC_IBEX_COSIM
ibex_cosim_agent cosim_agent;
`endif
core_ibex_vseqr vseqr;
core_ibex_env_cfg cfg;
@ -26,6 +29,14 @@ class core_ibex_env extends uvm_env;
instr_if_response_agent = ibex_mem_intf_response_agent::type_id::
create("instr_if_response_agent", this);
irq_agent = irq_request_agent::type_id::create("irq_agent", this);
`ifdef INC_IBEX_COSIM
if (!cfg.disable_cosim) begin
cosim_agent = ibex_cosim_agent::type_id::create("cosim_agent", this);
end else begin
cosim_agent = null;
end
`endif
// Create virtual sequencer
vseqr = core_ibex_vseqr::type_id::create("vseqr", this);
endfunction : build_phase
@ -35,6 +46,15 @@ class core_ibex_env extends uvm_env;
vseqr.data_if_seqr = data_if_response_agent.sequencer;
vseqr.instr_if_seqr = instr_if_response_agent.sequencer;
vseqr.irq_seqr = irq_agent.sequencer;
`ifdef INC_IBEX_COSIM
if (cosim_agent != null) begin
data_if_response_agent.monitor.item_collected_port.connect(
cosim_agent.dmem_port);
instr_if_response_agent.monitor.item_collected_port.connect(
cosim_agent.imem_port);
end
`endif
endfunction : connect_phase
function void reset();

View file

@ -9,6 +9,7 @@ class core_ibex_env_cfg extends uvm_object;
bit enable_irq_nmi_seq;
bit enable_nested_irq;
bit enable_debug_seq;
bit disable_cosim;
bit[31:0] max_interval;
bit require_signature_addr;
string signature_addr_str;
@ -20,6 +21,7 @@ class core_ibex_env_cfg extends uvm_object;
`uvm_field_int(enable_irq_nmi_seq, UVM_DEFAULT)
`uvm_field_int(enable_nested_irq, UVM_DEFAULT)
`uvm_field_int(enable_debug_seq, UVM_DEFAULT)
`uvm_field_int(disable_cosim, UVM_DEFAULT)
`uvm_field_int(max_interval, UVM_DEFAULT)
`uvm_field_int(require_signature_addr, UVM_DEFAULT)
`uvm_field_int(signature_addr, UVM_DEFAULT)
@ -32,6 +34,7 @@ class core_ibex_env_cfg extends uvm_object;
void'($value$plusargs("enable_irq_nmi_seq=%0d", enable_irq_nmi_seq));
void'($value$plusargs("enable_nested_irq=%0d", enable_nested_irq));
void'($value$plusargs("enable_debug_seq=%0d", enable_debug_seq));
void'($value$plusargs("disable_cosim=%0d", disable_cosim));
void'($value$plusargs("max_interval=%0d", max_interval));
void'($value$plusargs("require_signature_addr=%0d", require_signature_addr));
void'($value$plusargs("signature_addr=%s", signature_addr_str));

View file

@ -11,6 +11,7 @@ package core_ibex_env_pkg;
import uvm_pkg::*;
import ibex_mem_intf_agent_pkg::*;
import irq_agent_pkg::*;
import ibex_cosim_agent_pkg::*;
`include "core_ibex_vseqr.sv"
`include "core_ibex_env_cfg.sv"

View file

@ -13,7 +13,9 @@ interface core_ibex_instr_monitor_if #(
);
// ID stage
logic reset;
logic valid_id;
logic instr_new_id;
logic err_id;
logic is_compressed_id;
logic [15:0] instr_compressed_id;
@ -23,9 +25,12 @@ interface core_ibex_instr_monitor_if #(
logic [DATA_WIDTH-1:0] branch_target_id;
logic stall_id;
logic jump_set_id;
logic [63:0] rvfi_order_id;
clocking instr_cb @(posedge clk);
input reset;
input valid_id;
input instr_new_id;
input err_id;
input is_compressed_id;
input instr_compressed_id;
@ -35,6 +40,7 @@ interface core_ibex_instr_monitor_if #(
input branch_target_id;
input stall_id;
input jump_set_id;
input rvfi_order_id;
endclocking
endinterface

View file

@ -4,6 +4,7 @@
// Interface to probe Ibex RVFI interface
interface core_ibex_rvfi_if(input logic clk);
logic reset;
logic valid;
logic [63:0] order;
logic [31:0] insn;
@ -25,4 +26,41 @@ interface core_ibex_rvfi_if(input logic clk);
logic [3:0] mem_wmask;
logic [31:0] mem_rdata;
logic [31:0] mem_wdata;
logic [31:0] ext_mip;
logic ext_nmi;
logic [31:0] ext_debug_req;
logic [63:0] ext_mcycle;
clocking monitor_cb @(posedge clk);
input reset;
input valid;
input order;
input insn;
input trap;
input halt;
input intr;
input mode;
input ixl;
input rs1_addr;
input rs2_addr;
input rs1_rdata;
input rs2_rdata;
input rd_addr;
input rd_wdata;
input pc_rdata;
input pc_wdata;
input mem_addr;
input mem_rmask;
input mem_wmask;
input mem_rdata;
input mem_wdata;
input ext_mip;
input ext_nmi;
input ext_debug_req;
input ext_mcycle;
endclocking
task automatic wait_clks(input int num);
repeat (num) @(posedge clk);
endtask
endinterface

View file

@ -76,9 +76,11 @@ ${PRJ_DIR}/vendor/google_riscv-dv/src/riscv_signature_pkg.sv
+incdir+${PRJ_DIR}/dv/uvm/core_ibex/tests
+incdir+${PRJ_DIR}/dv/uvm/core_ibex/common/ibex_mem_intf_agent
+incdir+${PRJ_DIR}/dv/uvm/core_ibex/common/irq_agent
+incdir+${PRJ_DIR}/dv/uvm/core_ibex/common/ibex_cosim_agent
+incdir+${PRJ_DIR}/vendor/lowrisc_ip/dv/sv/mem_model
+incdir+${PRJ_DIR}/vendor/lowrisc_ip/dv/sv/dv_utils
+incdir+${PRJ_DIR}/vendor/lowrisc_ip/dv/sv/str_utils
+incdir+${PRJ_DIR}/dv/cosim
${PRJ_DIR}/dv/uvm/bus_params_pkg/bus_params_pkg.sv
${PRJ_DIR}/vendor/lowrisc_ip/dv/sv/common_ifs/clk_rst_if.sv
${PRJ_DIR}/vendor/lowrisc_ip/dv/sv/common_ifs/pins_if.sv
@ -90,9 +92,11 @@ ${PRJ_DIR}/dv/uvm/core_ibex/common/ibex_mem_intf_agent/ibex_mem_intf.sv
${PRJ_DIR}/dv/uvm/core_ibex/common/ibex_mem_intf_agent/ibex_mem_intf_agent_pkg.sv
${PRJ_DIR}/dv/uvm/core_ibex/common/irq_agent/irq_if.sv
${PRJ_DIR}/dv/uvm/core_ibex/common/irq_agent/irq_agent_pkg.sv
${PRJ_DIR}/dv/uvm/core_ibex/env/core_ibex_rvfi_if.sv
${PRJ_DIR}/dv/uvm/core_ibex/common/ibex_cosim_agent/core_ibex_ifetch_if.sv
${PRJ_DIR}/dv/uvm/core_ibex/common/ibex_cosim_agent/ibex_cosim_agent_pkg.sv
${PRJ_DIR}/dv/uvm/core_ibex/env/core_ibex_instr_monitor_if.sv
${PRJ_DIR}/dv/uvm/core_ibex/env/core_ibex_dut_probe_if.sv
${PRJ_DIR}/dv/uvm/core_ibex/env/core_ibex_rvfi_if.sv
${PRJ_DIR}/dv/uvm/core_ibex/env/core_ibex_csr_if.sv
${PRJ_DIR}/dv/uvm/core_ibex/env/core_ibex_env_pkg.sv
${PRJ_DIR}/dv/uvm/core_ibex/tests/core_ibex_test_pkg.sv

View file

@ -0,0 +1,7 @@
// Copyright lowRISC contributors.
// Licensed under the Apache License, Version 2.0, see LICENSE for details.
// SPDX-License-Identifier: Apache-2.0
${PRJ_DIR}/dv/uvm/core_ibex/common/ibex_cosim_agent/spike_cosim_dpi.cc
${PRJ_DIR}/dv/cosim/cosim_dpi.cc
${PRJ_DIR}/dv/cosim/spike_cosim.cc

View file

@ -430,7 +430,6 @@
+no_csr_instr=0
+no_ebreak=1
+no_fence=0
+no_wfi=0
+directed_instr_0=riscv_load_store_rand_instr_stream,40
+directed_instr_1=riscv_load_store_hazard_instr_stream,40
rtl_test: core_ibex_interrupt_instr_test
@ -482,6 +481,8 @@
iterations: 5
no_iss: 1
rtl_test: core_ibex_csr_test
sim_opts: >
+disable_cosim=1
no_post_compare: true
- test: riscv_unaligned_load_store_test
@ -712,6 +713,8 @@
# rtl_params:
# PMPEnable: 1
# Disable cosim for bitmanip tests for now as Ibex implements a different
# version of the spec compared to the Spike version used for the cosim.
- test: riscv_bitmanip_full_test
desc: >
Random instruction test with supported B extension instructions in full configuration
@ -720,6 +723,7 @@
gen_opts: >
+enable_b_extension=1
+enable_bitmanip_groups=zbb,zb_tmp,zbt,zbs,zbp,zbf,zbe,zbc,zbr
+disable_cosim=1
rtl_test: core_ibex_base_test
rtl_params:
RV32B: "ibex_pkg::RV32BFull"
@ -732,6 +736,7 @@
gen_opts: >
+enable_b_extension=1
+enable_bitmanip_groups=zbb,zb_tmp,zbt,zbs,zbf
+disable_cosim=1
rtl_test: core_ibex_base_test
rtl_params:
RV32B: ["ibex_pkg::RV32BFull", "ibex_pkg::RV32BBalanced"]

View file

@ -153,6 +153,8 @@ def main():
help="Enable coverage dump")
parser.add_argument("--en_wave", action='store_true',
help="Enable waveform dump")
parser.add_argument("--en_cosim", action='store_true',
help="Enable cosimulation")
parser.add_argument("--steps", type=str, default="all",
help="Run steps: compile,cov")
parser.add_argument("--lsf_cmd", type=str,
@ -182,7 +184,8 @@ def main():
if steps['compile']:
enables = {
'cov_opts': args.en_cov,
'wave_opts': args.en_wave
'wave_opts': args.en_wave,
'cosim_opts': args.en_cosim
}
compile_cmds, sim_cmd = get_simulator_cmd(args.simulator,
args.simulator_yaml, enables)

View file

@ -30,6 +30,8 @@ module core_ibex_tb_top;
// CSR access interface
core_ibex_csr_if csr_if(.clk(clk));
core_ibex_ifetch_if ifetch_if(.clk(clk));
// VCS does not support overriding enum and string parameters via command line. Instead, a
// `define is used that can be set from the command line. If no value has been specified, this
// gives a default. Other simulators don't take the detour via `define and can override the
@ -133,6 +135,7 @@ module core_ibex_tb_top;
assign instr_mem_vif.be = 0;
assign instr_mem_vif.wdata = 0;
// RVFI interface connections
assign rvfi_if.reset = ~rst_n;
assign rvfi_if.valid = dut.rvfi_valid;
assign rvfi_if.order = dut.rvfi_order;
assign rvfi_if.insn = dut.rvfi_insn;
@ -152,6 +155,10 @@ module core_ibex_tb_top;
assign rvfi_if.mem_rmask = dut.rvfi_mem_rmask;
assign rvfi_if.mem_rdata = dut.rvfi_mem_rdata;
assign rvfi_if.mem_wdata = dut.rvfi_mem_wdata;
assign rvfi_if.ext_mip = dut.rvfi_ext_mip;
assign rvfi_if.ext_nmi = dut.rvfi_ext_nmi;
assign rvfi_if.ext_debug_req = dut.rvfi_ext_debug_req;
assign rvfi_if.ext_mcycle = dut.rvfi_ext_mcycle;
// Irq interface connections
assign irq_vif.reset = ~rst_n;
// Dut_if interface connections
@ -164,16 +171,29 @@ module core_ibex_tb_top;
assign dut_if.reset = ~rst_n;
assign dut_if.priv_mode = dut.u_ibex_top.u_ibex_core.priv_mode_id;
// Instruction monitor connections
assign instr_monitor_if.reset = ~rst_n;
assign instr_monitor_if.valid_id = dut.u_ibex_top.u_ibex_core.id_stage_i.instr_valid_i;
assign instr_monitor_if.err_id = dut.u_ibex_top.u_ibex_core.id_stage_i.controller_i.instr_fetch_err;
assign instr_monitor_if.is_compressed_id = dut.u_ibex_top.u_ibex_core.id_stage_i.instr_is_compressed_i;
assign instr_monitor_if.instr_compressed_id = dut.u_ibex_top.u_ibex_core.id_stage_i.instr_rdata_c_i;
assign instr_monitor_if.instr_new_id = dut.u_ibex_top.u_ibex_core.instr_new_id;
assign instr_monitor_if.err_id =
dut.u_ibex_top.u_ibex_core.id_stage_i.controller_i.instr_fetch_err;
assign instr_monitor_if.is_compressed_id =
dut.u_ibex_top.u_ibex_core.id_stage_i.instr_is_compressed_i;
assign instr_monitor_if.instr_compressed_id =
dut.u_ibex_top.u_ibex_core.id_stage_i.instr_rdata_c_i;
assign instr_monitor_if.instr_id = dut.u_ibex_top.u_ibex_core.id_stage_i.instr_rdata_i;
assign instr_monitor_if.pc_id = dut.u_ibex_top.u_ibex_core.pc_id;
assign instr_monitor_if.branch_taken_id = dut.u_ibex_top.u_ibex_core.id_stage_i.controller_i.branch_set_i;
assign instr_monitor_if.branch_taken_id =
dut.u_ibex_top.u_ibex_core.id_stage_i.controller_i.branch_set_i;
assign instr_monitor_if.branch_target_id = dut.u_ibex_top.u_ibex_core.branch_target_ex;
assign instr_monitor_if.stall_id = dut.u_ibex_top.u_ibex_core.id_stage_i.stall_id;
assign instr_monitor_if.jump_set_id = dut.u_ibex_top.u_ibex_core.id_stage_i.jump_set;
assign instr_monitor_if.rvfi_order_id = dut.u_ibex_top.u_ibex_core.rvfi_stage_order_d;
// CSR interface connections
assign csr_if.csr_access = dut.u_ibex_top.u_ibex_core.csr_access;
assign csr_if.csr_addr = dut.u_ibex_top.u_ibex_core.csr_addr;
@ -181,6 +201,22 @@ module core_ibex_tb_top;
assign csr_if.csr_rdata = dut.u_ibex_top.u_ibex_core.csr_rdata;
assign csr_if.csr_op = dut.u_ibex_top.u_ibex_core.csr_op;
assign ifetch_if.reset = ~dut.u_ibex_top.u_ibex_core.if_stage_i.rst_ni;
assign ifetch_if.fetch_ready = dut.u_ibex_top.u_ibex_core.if_stage_i.fetch_ready;
assign ifetch_if.fetch_valid = dut.u_ibex_top.u_ibex_core.if_stage_i.fetch_valid;
assign ifetch_if.fetch_rdata = dut.u_ibex_top.u_ibex_core.if_stage_i.fetch_rdata;
assign ifetch_if.fetch_addr = dut.u_ibex_top.u_ibex_core.if_stage_i.fetch_addr;
assign ifetch_if.fetch_err = dut.u_ibex_top.u_ibex_core.if_stage_i.fetch_err;
assign ifetch_if.fetch_err_plus2 = dut.u_ibex_top.u_ibex_core.if_stage_i.fetch_err_plus2;
assign data_mem_vif.misaligned_first =
dut.u_ibex_top.u_ibex_core.load_store_unit_i.handle_misaligned_d |
((dut.u_ibex_top.u_ibex_core.load_store_unit_i.lsu_type_i == 2'b01) &
(dut.u_ibex_top.u_ibex_core.load_store_unit_i.data_offset == 2'b01));
assign data_mem_vif.misaligned_second =
dut.u_ibex_top.u_ibex_core.load_store_unit_i.addr_incr_req_o;
initial begin
// Drive the clock and reset lines. Reset everything and start the clock at the beginning of
// time
@ -200,6 +236,7 @@ module core_ibex_tb_top;
uvm_config_db#(virtual ibex_mem_intf)::set(null, "*data_if_response*", "vif", data_mem_vif);
uvm_config_db#(virtual ibex_mem_intf)::set(null, "*instr_if_response*", "vif", instr_mem_vif);
uvm_config_db#(virtual irq_if)::set(null, "*", "vif", irq_vif);
uvm_config_db#(virtual core_ibex_ifetch_if)::set(null, "*", "ifetch_if", ifetch_if);
run_test();
end

View file

@ -6,6 +6,9 @@ class core_ibex_base_test extends uvm_test;
core_ibex_env env;
core_ibex_env_cfg cfg;
`ifdef INC_IBEX_COSIM
core_ibex_cosim_cfg cosim_cfg;
`endif
virtual clk_rst_if clk_vif;
virtual core_ibex_dut_probe_if dut_vif;
virtual core_ibex_instr_monitor_if instr_vif;
@ -37,6 +40,8 @@ class core_ibex_base_test extends uvm_test;
endfunction
virtual function void build_phase(uvm_phase phase);
string cosim_log_file;
super.build_phase(phase);
$value$plusargs("timeout_in_cycles=%0d", timeout_in_cycles);
if (!uvm_config_db#(virtual clk_rst_if)::get(null, "", "clk_if", clk_vif)) begin
@ -55,6 +60,19 @@ class core_ibex_base_test extends uvm_test;
end
env = core_ibex_env::type_id::create("env", this);
cfg = core_ibex_env_cfg::type_id::create("cfg", this);
`ifdef INC_IBEX_COSIM
cosim_cfg = core_ibex_cosim_cfg::type_id::create("cosim_cfg", this);
cosim_cfg.start_pc = {{32'h`BOOT_ADDR}[31:8], 8'h80};
cosim_cfg.start_mtvec = {{32'h`BOOT_ADDR}[31:8], 8'h1};
// TODO: Turn on when not using icache
cosim_cfg.probe_imem_for_errs = 1'b0;
void'($value$plusargs("cosim_log_file=%0s", cosim_log_file));
cosim_cfg.log_file = cosim_log_file;
uvm_config_db#(core_ibex_cosim_cfg)::set(null, "*cosim_agent*", "cosim_cfg", cosim_cfg);
`endif
uvm_config_db#(core_ibex_env_cfg)::set(this, "*", "cfg", cfg);
mem = mem_model_pkg::mem_model#()::type_id::create("mem");
// Create virtual sequence and assign memory handle
@ -116,6 +134,11 @@ class core_ibex_base_test extends uvm_test;
while ($fread(r8,f_bin)) begin
`uvm_info(`gfn, $sformatf("Init mem [0x%h] = 0x%0h", addr, r8), UVM_FULL)
mem.write(addr, r8);
`ifdef INC_IBEX_COSIM
if (env.cosim_agent != null) begin
env.cosim_agent.write_mem_byte(addr, r8);
end
`endif
addr++;
end
endfunction

View file

@ -13,6 +13,7 @@ package core_ibex_test_pkg;
import irq_agent_pkg::*;
import riscv_signature_pkg::*;
import ibex_pkg::*;
import ibex_cosim_agent_pkg::*;
typedef struct {
ibex_pkg::opcode_e opcode;

View file

@ -17,6 +17,7 @@
# As a result, passing -fno-extended-identifiers tells G++ to pretend that
# everything is ASCII, preventing strange compilation errors.
- tool: vcs
env_var: IBEX_COSIM_ISS_ROOT,IBEX_ROOT
compile:
cmd:
- "vcs -f ibex_dv.f -full64
@ -31,7 +32,7 @@
-debug_access+pp
-xlrm uniq_prior_final
-CFLAGS '--std=c99 -fno-extended-identifiers'
-lca -kdb <cmp_opts> <wave_opts> <cov_opts>"
-lca -kdb <cmp_opts> <wave_opts> <cov_opts> <cosim_opts>"
cov_opts: >
-cm line+tgl+assert+fsm+branch
-cm_tgl portsonly
@ -42,12 +43,20 @@
-cm_hier cover.cfg
wave_opts: >
-debug_access+all -ucli -do vcs.tcl
cosim_opts: >
-f ibex_dv_cosim_dpi.f
+define+INC_IBEX_COSIM
-LDFLAGS '-L<IBEX_COSIM_ISS_ROOT>/lib/'
-CFLAGS '-I<IBEX_COSIM_ISS_ROOT>/include/riscv -I<IBEX_COSIM_ISS_ROOT>/include/softfloat'
-CFLAGS '-I<IBEX_COSIM_ISS_ROOT>/include/fesvr -I<IBEX_ROOT>/dv/cosim'
-lriscv -lsoftfloat -lfdt -ldl -ldisasm -lstdc++
sim:
cmd: >
env SIM_DIR=<sim_dir>
<out>/vcs_simv +vcs+lic+wait <sim_opts> <wave_opts> <cov_opts>
+ntb_random_seed=<seed> +UVM_TESTNAME=<rtl_test> +bin=<binary>
+ibex_tracer_file_base=<sim_dir>/trace_core
+cosim_log_file=<sim_dir>/spike_cosim.log
cov_opts: >
-cm line+tgl+assert+fsm+branch
-cm_dir <out>/test.vdb