Merge branch 'main' of https://github.com/openhwgroup/cvw into bit-manip

This commit is contained in:
Kevin Kim 2023-03-21 11:20:05 -07:00
commit 2e149f9a31
26 changed files with 308 additions and 81 deletions

9
.gitignore vendored
View File

@ -103,4 +103,11 @@ external
sim/results
tests/wally-riscv-arch-test/riscv-test-suite/rv*i_m/I/src/*.S
tests/wally-riscv-arch-test/riscv-test-suite/rv*i_m/I/Makefrag
sim/branch_BP_GSHARE10.log
sim/branch_BP_GSHARE16.log
sim/cov/
sim/covhtmlreport/
sim/imperas.log
sim/results-error/
sim/test1.rep
sim/vsim.log

36
LICENSE
View File

@ -1,22 +1,14 @@
MIT License
Copyright (c) 2021 Harvey Mudd College & Oklahoma State University
Contact: Prof. David Harris David_Harris@hmc.edu
Permission is hereby granted, free of charge, to any person obtaining a copy
of this software and associated documentation files (the "Software"), to deal
in the Software without restriction, including without limitation the rights
to use, copy, modify, merge, publish, distribute, sublicense, and/or sell
copies of the Software, and to permit persons to whom the Software is
furnished to do so, subject to the following conditions:
The above copyright notice and this permission notice shall be included in all
copies or substantial portions of the Software.
THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING FROM,
OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS IN THE
SOFTWARE.
// Copyright (C) 2021-23 Harvey Mudd College & Oklahoma State University
//
// SPDX-License-Identifier: Apache-2.0 WITH SHL-2.1
//
// Licensed under the Solderpad Hardware License v 2.1 (the “License”); you may not use this file
// except in compliance with the License, or, at your option, the Apache License version 2.0. You
// may obtain a copy of the License at
//
// https://solderpad.org/licenses/SHL-2.1/
//
// Unless required by applicable law or agreed to in writing, any work distributed under the
// License is distributed on an “AS IS” BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND,
// either express or implied. See the License for the specific language governing permissions
// and limitations under the License.

View File

@ -115,9 +115,12 @@ opam install sail -y
eval $(opam config env)
git clone https://github.com/riscv/sail-riscv.git
cd sail-riscv
# Current bug in Sail - use hash that works for Wally
# (may remove later if Sail is ever fixed)
git checkout 4d05aa1698a0003a4f6f99e1380c743711c32052
make -j ${NUM_THREADS}
ARCH=RV32 make
ARCH=RV64 make
ARCH=RV32 make -j ${NUM_THREADS}
ARCH=RV64 make -j ${NUM_THREADS}
ln -sf $RISCV/sail-riscv/c_emulator/riscv_sim_RV64 /usr/bin/riscv_sim_RV64
ln -sf $RISCV/sail-riscv/c_emulator/riscv_sim_RV32 /usr/bin/riscv_sim_RV32

View File

@ -12,6 +12,8 @@ SECTIONS
.data.string : { *(.data.string)}
. = ALIGN(0x1000);
.bss : { *(.bss) }
. = ALIGN(0x1000);
.text : { *(.text.main) }
_end = .;
}

View File

@ -0,0 +1,34 @@
#///////////////////////////////////////////
#// coverage-exclusions-rv64gc.do
#//
#// Written: David_Harris@hmc.edu 19 March 2023
#//
#// Purpose: Set of exclusions from coverage for rv64gc configuration
#// For example, signals hardwired to 0 should not be checked for toggle coverage
#//
#// A component of the CORE-V-WALLY configurable RISC-V project.
#//
#// Copyright (C) 2021-23 Harvey Mudd College & Oklahoma State University
#//
#// SPDX-License-Identifier: Apache-2.0 WITH SHL-2.1
#//
#// Licensed under the Solderpad Hardware License v 2.1 (the “License”); you may not use this file
#// except in compliance with the License, or, at your option, the Apache License version 2.0. You
#// may obtain a copy of the License at
#//
#// https://solderpad.org/licenses/SHL-2.1/
#//
#// Unless required by applicable law or agreed to in writing, any work distributed under the
#// License is distributed on an “AS IS” BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND,
#// either express or implied. See the License for the specific language governing permissions
#// and limitations under the License.
#////////////////////////////////////////////////////////////////////////////////////////////////
# Exclude DivBusyE from all design units because rv64gc uses the fdivsqrt unit for integer division
coverage exclude -togglenode DivBusyE -du *
# Exclude QuotM and RemM from MDU because rv64gc uses the fdivsqrt rather tha div unit for integer division
coverage exclude -togglenode /dut/core/mdu/mdu/QuotM
coverage exclude -togglenode /dut/core/mdu/mdu/RemM
# StallFCause is hardwired to 0
coverage exclude -togglenode /dut/core/hzu/StallFCause

View File

@ -217,8 +217,10 @@ def main():
if coverage:
print('Generating coverage report')
os.system('vcover merge -out cov/cov.ucdb cov/rv64gc_arch64i.ucdb cov/rv64gc*.ucdb -logfile cov/log')
os.system('vcover report -details cov/cov.ucdb > cov/rv64gc_coverage.rpt')
os.system('vcover report -html cov/cov.ucdb')
os.system('vcover report -details cov/cov.ucdb > cov/rv64gc_coverage_details.rpt')
os.system('vcover report -below 100 cov/cov.ucdb > cov/rv64gc_coverage.rpt')
os.system('vcover report -recursive cov/cov.ucdb > cov/rv64gc_recursive.rpt')
os.system('vcover report -details -threshH 100 -html cov/cov.ucdb')
# Count the number of failures
if num_fail:
print(f"{bcolors.FAIL}Regression failed with %s failed configurations{bcolors.ENDC}" % num_fail)

View File

@ -124,7 +124,8 @@ if {$2 eq "buildroot" || $2 eq "buildroot-checkpoint"} {
# start and run simulation
# remove +acc flag for faster sim during regressions if there is no need to access internal signals
if {$coverage} {
vopt wkdir/work_${1}_${2}.testbench -work wkdir/work_${1}_${2} -G TEST=$2 -o testbenchopt +cover=sbectf
# vopt wkdir/work_${1}_${2}.testbench -work wkdir/work_${1}_${2} -G TEST=$2 -o testbenchopt +cover=sbectf
vopt wkdir/work_${1}_${2}.testbench -work wkdir/work_${1}_${2} -G TEST=$2 -o testbenchopt +cover=sbecf
vsim -lib wkdir/work_${1}_${2} testbenchopt -fatal 7 -suppress 3829 -coverage
} else {
vopt wkdir/work_${1}_${2}.testbench -work wkdir/work_${1}_${2} -G TEST=$2 -o testbenchopt
@ -138,8 +139,8 @@ if {$2 eq "buildroot" || $2 eq "buildroot-checkpoint"} {
}
if {$coverage} {
do coverage-exclusions.do
coverage save -instance /testbench/dut cov/${1}_${2}.ucdb
do coverage-exclusions-rv64gc.do # beware: this assumes testing the rv64gc configuration
coverage save -instance /testbench/dut/core cov/${1}_${2}.ucdb
}
# These aren't doing anything helpful

2
src/cache/cache.sv vendored
View File

@ -197,7 +197,7 @@ module cache #(parameter LINELEN, NUMLINES, NUMWAYS, LOGBWPL, WORDLEN, MUXINTE
// Cache FSM
/////////////////////////////////////////////////////////////////////////////////////////////
cachefsm cachefsm(.clk, .reset, .CacheBusRW, .CacheBusAck,
cachefsm #(READ_ONLY_CACHE) cachefsm(.clk, .reset, .CacheBusRW, .CacheBusAck,
.FlushStage, .CacheRW, .CacheAtomic, .Stall,
.CacheHit, .LineDirty, .CacheStall, .CacheCommitted,
.CacheMiss, .CacheAccess, .SelAdr,

16
src/cache/cachefsm.sv vendored
View File

@ -29,7 +29,7 @@
`include "wally-config.vh"
module cachefsm (
module cachefsm #(parameter READ_ONLY_CACHE = 0) (
input logic clk,
input logic reset,
// hazard and privilege unit
@ -112,8 +112,8 @@ module cachefsm (
NextState = STATE_READY;
case (CurrState)
STATE_READY: if(InvalidateCache) NextState = STATE_READY;
else if(FlushCache) NextState = STATE_FLUSH;
else if(AnyMiss & ~LineDirty) NextState = STATE_FETCH;
else if(FlushCache & ~READ_ONLY_CACHE) NextState = STATE_FLUSH;
else if(AnyMiss & (READ_ONLY_CACHE | ~LineDirty)) NextState = STATE_FETCH;
else if(AnyMiss & LineDirty) NextState = STATE_WRITEBACK;
else NextState = STATE_READY;
STATE_FETCH: if(CacheBusAck) NextState = STATE_WRITE_LINE;
@ -125,11 +125,11 @@ module cachefsm (
else NextState = STATE_WRITEBACK;
// eviction needs a delay as the bus fsm does not correctly handle sending the write command at the same time as getting back the bus ack.
STATE_FLUSH: if(LineDirty) NextState = STATE_FLUSH_WRITEBACK;
else if (FlushFlag) NextState = STATE_READ_HOLD;
else NextState = STATE_FLUSH;
STATE_FLUSH_WRITEBACK: if(CacheBusAck & ~FlushFlag) NextState = STATE_FLUSH;
else if(CacheBusAck) NextState = STATE_READ_HOLD;
else NextState = STATE_FLUSH_WRITEBACK;
else if (FlushFlag) NextState = STATE_READ_HOLD;
else NextState = STATE_FLUSH;
STATE_FLUSH_WRITEBACK: if(CacheBusAck & ~FlushFlag) NextState = STATE_FLUSH;
else if(CacheBusAck) NextState = STATE_READ_HOLD;
else NextState = STATE_FLUSH_WRITEBACK;
default: NextState = STATE_READY;
endcase
end

View File

@ -71,7 +71,6 @@ module controller(
output logic RegWriteM, // Instruction writes a register (needed for Hazard unit)
output logic InvalidateICacheM, FlushDCacheM, // Invalidate I$, flush D$
output logic InstrValidD, InstrValidE, InstrValidM, // Instruction is valid
output logic FenceM, // Fence instruction
output logic FWriteIntM, // FPU controller writes integer register file
// Writeback stage control signals
input logic StallW, FlushW, // Stall, flush Writeback stage
@ -136,6 +135,7 @@ module controller(
logic IFunctD, RFunctD, MFunctD; // Detect I, R, and M-type RV32IM/Rv64IM instructions
logic LFunctD, SFunctD, BFunctD; // Detect load, store, branch instructions
logic JFunctD; // detect jalr instruction
logic FenceM; // Fence.I or sfence.VMA instruction in memory stage
// Extract fields
assign OpD = InstrD[6:0];
@ -335,7 +335,6 @@ module controller(
// Flush F, D, and E stages on a CSR write or Fence.I or SFence.VMA
assign CSRWriteFenceM = CSRWriteM | FenceM;
// assign CSRWriteFencePendingDEM = CSRWriteD | CSRWriteE | CSRWriteM | FenceD | FenceE | FenceM;
// the synchronous DTIM cannot read immediately after write
// a cache cannot read or write immediately after a write

View File

@ -71,8 +71,7 @@ module ieu (
output logic FCvtIntStallD, LoadStallD, // Stall causes from IEU to hazard unit
output logic MDUStallD, CSRRdStallD, StoreStallD,
output logic CSRReadM, CSRWriteM, PrivilegedM,// CSR read, CSR write, is privileged instruction
output logic CSRWriteFenceM, // CSR write or fence instruction needs to flush subsequent instructions
output logic FenceM
output logic CSRWriteFenceM // CSR write or fence instruction needs to flush subsequent instructions
);
logic [2:0] ImmSrcD; // Select type of immediate extension
@ -103,8 +102,8 @@ controller c(
.PCSrcE, .ALUControlE, .ALUSrcAE, .ALUSrcBE, .ALUResultSrcE, .ALUSelectE, .MemReadE, .CSRReadE,
.Funct3E, .IntDivE, .MDUE, .W64E, .BranchD, .BranchE, .JumpD, .JumpE, .SCE, .BranchSignedE, .BSelectE, .ZBBSelectE, .BALUControlE, .StallM, .FlushM, .MemRWM,
.CSRReadM, .CSRWriteM, .PrivilegedM, .AtomicM, .Funct3M,
.RegWriteM, .InvalidateICacheM, .FlushDCacheM, .InstrValidM, .InstrValidE, .InstrValidD, .FWriteIntM,
.StallW, .FlushW, .RegWriteW, .IntDivW, .ResultSrcW, .CSRWriteFenceM, .FenceM, .StoreStallD);
.RegWriteM, .FlushDCacheM, .InstrValidM, .InstrValidE, .InstrValidD, .FWriteIntM,
.StallW, .FlushW, .RegWriteW, .IntDivW, .ResultSrcW, .CSRWriteFenceM, .InvalidateICacheM, .StoreStallD);
datapath dp(
.clk, .reset, .ImmSrcD, .InstrD, .StallE, .FlushE, .ForwardAE, .ForwardBE,

View File

@ -87,7 +87,8 @@ module subwordread
3'b001: ReadDataM = {{`LLEN-16{HalfwordM[15]|FpLoadStoreM}}, HalfwordM[15:0]}; // lh/flh
3'b010: ReadDataM = {{`LLEN-32{WordM[31]|FpLoadStoreM}}, WordM[31:0]}; // lw/flw
3'b011: ReadDataM = {{`LLEN-64{DblWordM[63]|FpLoadStoreM}}, DblWordM[63:0]}; // ld/fld
3'b100: ReadDataM = FpLoadStoreM ? ReadDataWordMuxM : {{`LLEN-8{1'b0}}, ByteM[7:0]}; // lbu/flq
3'b100: ReadDataM = {{`LLEN-8{1'b0}}, ByteM[7:0]}; // lbu
// 3'b100: ReadDataM = FpLoadStoreM ? ReadDataWordMuxM : {{`LLEN-8{1'b0}}, ByteM[7:0]}; // lbu/flq - only needed when LLEN=128
3'b101: ReadDataM = {{`LLEN-16{1'b0}}, HalfwordM[15:0]}; // lhu
3'b110: ReadDataM = {{`LLEN-32{1'b0}}, WordM[31:0]}; // lwu
default: ReadDataM = ReadDataWordMuxM; // Shouldn't happen

View File

@ -28,7 +28,7 @@
`include "wally-config.vh"
module intdivrestoring(
module div(
input logic clk,
input logic reset,
input logic StallM,
@ -107,7 +107,7 @@ module intdivrestoring(
// one copy of divstep for each bit produced per cycle
genvar i;
for (i=0; i<`IDIV_BITSPERCYCLE; i = i+1)
intdivrestoringstep divstep(W[i], XQ[i], DAbsB, W[i+1], XQ[i+1]);
divstep divstep(W[i], XQ[i], DAbsB, W[i+1], XQ[i+1]);
//////////////////////////////
// Memory Stage: output sign correction and special cases

View File

@ -4,7 +4,7 @@
// Written: David_Harris@hmc.edu 2 October 2021
// Modified:
//
// Purpose: Restoring integer division step. k steps are used in intdivrestoring
// Purpose: Radix-2 restoring integer division step. k steps are used in div
//
// Documentation: RISC-V System on Chip Design Chapter 12 (Figure 12.19)
//
@ -30,7 +30,7 @@
/* verilator lint_off UNOPTFLAT */
module intdivrestoringstep(
module divstep(
input logic [`XLEN-1:0] W, // Residual in
input logic [`XLEN-1:0] XQ, // bits of dividend X and quotient Q in
input logic [`XLEN-1:0] DAbsB, // complement of absolute value of divisor D (for subtraction)

View File

@ -57,8 +57,8 @@ module mdu(
assign RemM = 0;
assign DivBusyE = 0;
end else begin:div
intdivrestoring div(.clk, .reset, .StallM, .FlushE, .DivSignedE(~Funct3E[0]), .W64E, .IntDivE,
.ForwardedSrcAE, .ForwardedSrcBE, .DivBusyE, .QuotM, .RemM);
div div(.clk, .reset, .StallM, .FlushE, .DivSignedE(~Funct3E[0]), .W64E, .IntDivE,
.ForwardedSrcAE, .ForwardedSrcBE, .DivBusyE, .QuotM, .RemM);
end
// Result multiplexer

View File

@ -50,14 +50,14 @@ module pmpchecker (
);
// Bit i is high when the address falls in PMP region i
logic EnforcePMP;
logic [`PMP_ENTRIES-1:0] Match; // physical address matches one of the pmp ranges
logic EnforcePMP; // should PMP be checked in this privilege level
logic [`PMP_ENTRIES-1:0] Match; // physical address matches one of the pmp ranges
logic [`PMP_ENTRIES-1:0] FirstMatch; // onehot encoding for the first pmpaddr to match the current address.
logic [`PMP_ENTRIES-1:0] Active; // PMP register i is non-null
logic [`PMP_ENTRIES-1:0] L, X, W, R; // PMP matches and has flag set
logic [`PMP_ENTRIES-1:0] PAgePMPAdr; // for TOR PMP matching, PhysicalAddress > PMPAdr[i]
logic [`PMP_ENTRIES-1:0] PAgePMPAdr; // for TOR PMP matching, PhysicalAddress > PMPAdr[i]
if (`PMP_ENTRIES > 0)
if (`PMP_ENTRIES > 0) // prevent complaints about array of no elements when PMP_ENTRIES = 0
pmpadrdec pmpadrdecs[`PMP_ENTRIES-1:0](
.PhysicalAddress,
.PMPCfg(PMPCFG_ARRAY_REGW),
@ -68,8 +68,10 @@ module pmpchecker (
priorityonehot #(`PMP_ENTRIES) pmppriority(.a(Match), .y(FirstMatch)); // combine the match signal from all the adress decoders to find the first one that matches.
// Only enforce PMP checking for S and U modes when at least one PMP is active or in Machine mode when L bit is set in selected region
// Only enforce PMP checking for S and U modes or in Machine mode when L bit is set in selected region
assign EnforcePMP = (PrivilegeModeW == `M_MODE) ? |(L & FirstMatch) : |Active;
// assign EnforcePMP = (PrivilegeModeW != `M_MODE) | |(L & FirstMatch); // *** switch to this logic when PMP is initialized for non-machine mode
// *** remove unused Active lines from pmpadrdecs
assign PMPInstrAccessFaultF = EnforcePMP & ExecuteAccessF & ~|(X & FirstMatch) ;
assign PMPStoreAmoAccessFaultM = EnforcePMP & WriteAccessM & ~|(W & FirstMatch) ;

View File

@ -72,7 +72,7 @@ module csr #(parameter
input logic ICacheMiss,
input logic ICacheAccess,
input logic sfencevmaM,
input logic FenceM,
input logic InvalidateICacheM,
input logic DivBusyE, // integer divide busy
input logic FDivBusyE, // floating point divide busy
// outputs from CSRs
@ -210,7 +210,7 @@ module csr #(parameter
csri csri(.clk, .reset, .InstrValidNotFlushedM,
.CSRMWriteM, .CSRSWriteM, .CSRWriteValM, .CSRAdrM,
.MExtInt, .SExtInt, .MTimerInt, .STimerInt, .MSwInt,
.MIP_REGW, .MIE_REGW, .MIP_REGW_writeable);
.MIDELEG_REGW, .MIP_REGW, .MIE_REGW, .MIP_REGW_writeable);
csrsr csrsr(.clk, .reset, .StallW,
.WriteMSTATUSM, .WriteMSTATUSHM, .WriteSSTATUSM,
@ -268,7 +268,7 @@ module csr #(parameter
.InstrValidNotFlushedM, .LoadStallD, .StoreStallD, .CSRWriteM, .CSRMWriteM,
.BPDirPredWrongM, .BTAWrongM, .RASPredPCWrongM, .IClassWrongM, .BPWrongM,
.InstrClassM, .DCacheMiss, .DCacheAccess, .ICacheMiss, .ICacheAccess, .sfencevmaM,
.InterruptM, .ExceptionM, .FenceM, .ICacheStallF, .DCacheStallM, .DivBusyE, .FDivBusyE,
.InterruptM, .ExceptionM, .InvalidateICacheM, .ICacheStallF, .DCacheStallM, .DivBusyE, .FDivBusyE,
.CSRAdrM, .PrivilegeModeW, .CSRWriteValM,
.MCOUNTINHIBIT_REGW, .MCOUNTEREN_REGW, .SCOUNTEREN_REGW,
.MTIME_CLINT, .CSRCReadValM, .IllegalCSRCAccessM);

View File

@ -60,7 +60,7 @@ module csrc #(parameter
input logic sfencevmaM,
input logic InterruptM,
input logic ExceptionM,
input logic FenceM,
input logic InvalidateICacheM,
input logic DivBusyE, // integer divide busy
input logic FDivBusyE, // floating point divide busy
input logic [11:0] CSRAdrM,
@ -111,7 +111,7 @@ module csrc #(parameter
assign CounterEvent[17] = ICacheMiss; // instruction cache miss. Miss asserted 1 cycle at start of cache miss
assign CounterEvent[18] = ICacheStallF; // i cache miss cycles
assign CounterEvent[19] = CSRWriteM & InstrValidNotFlushedM; // CSR writes
assign CounterEvent[20] = FenceM & InstrValidNotFlushedM; // fence.i
assign CounterEvent[20] = InvalidateICacheM & InstrValidNotFlushedM; // fence.i
assign CounterEvent[21] = sfencevmaM & InstrValidNotFlushedM; // sfence.vma
assign CounterEvent[22] = InterruptM; // interrupt, InstrValidNotFlushedM will be low
assign CounterEvent[23] = ExceptionM; // exceptions, InstrValidNotFlushedM will be low

View File

@ -40,6 +40,7 @@ module csri #(parameter
input logic [`XLEN-1:0] CSRWriteValM,
input logic [11:0] CSRAdrM,
input logic MExtInt, SExtInt, MTimerInt, STimerInt, MSwInt,
input logic [11:0] MIDELEG_REGW,
output logic [11:0] MIP_REGW, MIE_REGW,
output logic [11:0] MIP_REGW_writeable // only SEIP, STIP, SSIP are actually writeable; the rest are hardwired to 0
);
@ -66,7 +67,7 @@ module csri #(parameter
assign MIP_WRITE_MASK = 12'h222; // SEIP, STIP, SSIP are writeable in MIP (20210108-draft 3.1.9)
assign STIP = MIP_REGW_writeable[5];
end
assign SIP_WRITE_MASK = 12'h002; // SSIP is writeable in SIP (privileged 20210108-draft 4.1.3)
assign SIP_WRITE_MASK = 12'h002 & MIDELEG_REGW; // SSIP is writeable in SIP (privileged 20210108-draft 4.1.3)
assign MIE_WRITE_MASK = 12'hAAA;
end else begin:mask
assign MIP_WRITE_MASK = 12'h000;
@ -80,7 +81,7 @@ module csri #(parameter
always @(posedge clk)
if (reset) MIE_REGW <= 12'b0;
else if (WriteMIEM) MIE_REGW <= (CSRWriteValM[11:0] & MIE_WRITE_MASK); // MIE controls M and S fields
else if (WriteSIEM) MIE_REGW <= (CSRWriteValM[11:0] & 12'h222) | (MIE_REGW & 12'h888); // only S fields
else if (WriteSIEM) MIE_REGW <= (CSRWriteValM[11:0] & 12'h222 & MIDELEG_REGW) | (MIE_REGW & 12'h888); // only S fields
assign MIP_REGW = {MExtInt, 1'b0, SExtInt|MIP_REGW_writeable[9], 1'b0,

View File

@ -123,7 +123,7 @@ module csrs #(parameter
SSTATUS: CSRSReadValM = SSTATUS_REGW;
STVEC: CSRSReadValM = STVEC_REGW;
SIP: CSRSReadValM = {{(`XLEN-12){1'b0}}, MIP_REGW & 12'h222 & MIDELEG_REGW}; // only read supervisor fields
SIE: CSRSReadValM = {{(`XLEN-12){1'b0}}, MIE_REGW & 12'h222}; // only read supervisor fields
SIE: CSRSReadValM = {{(`XLEN-12){1'b0}}, MIE_REGW & 12'h222 & MIDELEG_REGW}; // only read supervisor fields
SSCRATCH: CSRSReadValM = SSCRATCH_REGW;
SEPC: CSRSReadValM = SEPC_REGW;
SCAUSE: CSRSReadValM = SCAUSE_REGW;

View File

@ -88,7 +88,7 @@ module privileged (
// control outputs
output logic RetM, TrapM, // return instruction, or trap
output logic sfencevmaM, // sfence.vma instruction
input logic FenceM, // fence instruction
input logic InvalidateICacheM, // fence instruction
output logic BigEndianM, // Use big endian in current privilege mode
// Fault outputs
output logic BreakpointFaultM, EcallFaultM, // breakpoint and Ecall traps should retire
@ -131,7 +131,7 @@ module privileged (
.MTimerInt, .MExtInt, .SExtInt, .MSwInt,
.MTIME_CLINT, .InstrValidM, .FRegWriteM, .LoadStallD, .StoreStallD,
.BPDirPredWrongM, .BTAWrongM, .RASPredPCWrongM, .BPWrongM,
.sfencevmaM, .ExceptionM, .FenceM, .ICacheStallF, .DCacheStallM, .DivBusyE, .FDivBusyE,
.sfencevmaM, .ExceptionM, .InvalidateICacheM, .ICacheStallF, .DCacheStallM, .DivBusyE, .FDivBusyE,
.IClassWrongM, .InstrClassM, .DCacheMiss, .DCacheAccess, .ICacheMiss, .ICacheAccess,
.NextPrivilegeModeM, .PrivilegeModeW, .CauseM, .SelHPTW,
.STATUS_MPP, .STATUS_SPP, .STATUS_TSR, .STATUS_TVM,

View File

@ -161,7 +161,6 @@ module wallypipelinedcore (
logic FCvtIntE;
logic CommittedF;
logic BranchD, BranchE, JumpD, JumpE;
logic FenceM;
logic DCacheStallM, ICacheStallF;
// instruction fetch unit: PC, branch prediction, instruction cache
@ -201,7 +200,7 @@ module wallypipelinedcore (
.WriteDataM, // Write data to LSU
.Funct3M, // size and signedness to LSU
.SrcAM, // to privilege and fpu
.RdE, .RdM, .FIntResM, .InvalidateICacheM, .FlushDCacheM,
.RdE, .RdM, .FIntResM, .FlushDCacheM,
.BranchD, .BranchE, .JumpD, .JumpE,
// Writeback stage
.CSRReadValW, .MDUResultW, .FIntDivResultW, .RdW, .ReadDataW(ReadDataW[`XLEN-1:0]),
@ -209,7 +208,7 @@ module wallypipelinedcore (
// hazards
.StallD, .StallE, .StallM, .StallW, .FlushD, .FlushE, .FlushM, .FlushW,
.FCvtIntStallD, .LoadStallD, .MDUStallD, .CSRRdStallD, .PCSrcE,
.CSRReadM, .CSRWriteM, .PrivilegedM, .CSRWriteFenceM, .FenceM, .StoreStallD);
.CSRReadM, .CSRWriteM, .PrivilegedM, .CSRWriteFenceM, .InvalidateICacheM, .StoreStallD);
lsu lsu(
.clk, .reset, .StallM, .FlushM, .StallW, .FlushW,
@ -288,7 +287,7 @@ module wallypipelinedcore (
.FlushD, .FlushE, .FlushM, .FlushW, .StallD, .StallE, .StallM, .StallW,
.CSRReadM, .CSRWriteM, .SrcAM, .PCM, .PC2NextF,
.InstrM, .CSRReadValW, .UnalignedPCNextF,
.RetM, .TrapM, .sfencevmaM, .FenceM, .DCacheStallM, .ICacheStallF,
.RetM, .TrapM, .sfencevmaM, .InvalidateICacheM, .DCacheStallM, .ICacheStallF,
.InstrValidM, .CommittedM, .CommittedF,
.FRegWriteM, .LoadStallD, .StoreStallD,
.BPDirPredWrongM, .BTAWrongM, .BPWrongM,

View File

@ -1857,15 +1857,15 @@ string arch64zbs[] = '{
"rv64i_m/privilege/src/WALLY-mtvec-01.S",
"rv64i_m/privilege/src/WALLY-pma-01.S",
"rv64i_m/privilege/src/WALLY-pmp-01.S",
"rv64i_m/privilege/src/WALLY-sie-01.S",
// "rv64i_m/privilege/src/WALLY-sie-01.S",
"rv64i_m/privilege/src/WALLY-status-mie-01.S",
"rv64i_m/privilege/src/WALLY-status-sie-01.S",
// "rv64i_m/privilege/src/WALLY-status-sie-01.S",
"rv64i_m/privilege/src/WALLY-status-tw-01.S",
"rv64i_m/privilege/src/WALLY-status-tvm-01.S",
"rv64i_m/privilege/src/WALLY-status-fp-enabled-01.S",
"rv64i_m/privilege/src/WALLY-stvec-01.S",
"rv64i_m/privilege/src/WALLY-trap-01.S",
"rv64i_m/privilege/src/WALLY-trap-s-01.S",
// "rv64i_m/privilege/src/WALLY-stvec-01.S",
// "rv64i_m/privilege/src/WALLY-trap-01.S",
// "rv64i_m/privilege/src/WALLY-trap-s-01.S",
"rv64i_m/privilege/src/WALLY-trap-sret-01.S",
"rv64i_m/privilege/src/WALLY-trap-u-01.S",
"rv64i_m/privilege/src/WALLY-wfi-01.S",
@ -1945,15 +1945,15 @@ string arch64zbs[] = '{
"rv32i_m/privilege/src/WALLY-mtvec-01.S",
"rv32i_m/privilege/src/WALLY-pma-01.S",
"rv32i_m/privilege/src/WALLY-pmp-01.S",
"rv32i_m/privilege/src/WALLY-sie-01.S",
// "rv32i_m/privilege/src/WALLY-sie-01.S",
"rv32i_m/privilege/src/WALLY-status-mie-01.S",
"rv32i_m/privilege/src/WALLY-status-sie-01.S",
// "rv32i_m/privilege/src/WALLY-status-sie-01.S",
"rv32i_m/privilege/src/WALLY-status-tw-01.S",
"rv32i_m/privilege/src/WALLY-status-tvm-01.S",
"rv32i_m/privilege/src/WALLY-status-fp-enabled-01.S",
"rv32i_m/privilege/src/WALLY-stvec-01.S",
"rv32i_m/privilege/src/WALLY-trap-01.S",
"rv32i_m/privilege/src/WALLY-trap-s-01.S",
// "rv32i_m/privilege/src/WALLY-stvec-01.S",
// "rv32i_m/privilege/src/WALLY-trap-01.S",
// "rv32i_m/privilege/src/WALLY-trap-s-01.S",
"rv32i_m/privilege/src/WALLY-trap-sret-01.S",
"rv32i_m/privilege/src/WALLY-trap-u-01.S",
"rv32i_m/privilege/src/WALLY-wfi-01.S",

19
tests/coverage/Makefile Normal file
View File

@ -0,0 +1,19 @@
TARGET = badinstr
$(TARGET).objdump: $(TARGET)
riscv64-unknown-elf-objdump -D $(TARGET) > $(TARGET).objdump
$(TARGET): $(TARGET).S WALLY-init-lib.S Makefile
riscv64-unknown-elf-gcc -g -o $(TARGET) -march=rv64gc -mabi=lp64 -mcmodel=medany \
-nostartfiles -T../../examples/link/link.ld $(TARGET).S
sim:
spike +signature=$(TARGET).signature.output +signature-granularity=8 $(TARGET)
diff --ignore-case $(TARGET).signature.output $(TARGET).reference_output || exit
echo "Signature matches! Success!"
clean:
rm -f $(TARGET) $(TARGET).objdump $(TARGET).signature.output

View File

@ -0,0 +1,119 @@
///////////////////////////////////////////
// WALLY-init-lib.S
//
// Written: David_Harris@hmc.edu 21 March 2023
//
// Purpose: Initialize stack, handle interrupts, terminate test case
//
// A component of the CORE-V-WALLY configurable RISC-V project.
//
// Copyright (C) 2021-23 Harvey Mudd College & Oklahoma State University
//
// SPDX-License-Identifier: Apache-2.0 WITH SHL-2.1
//
// Licensed under the Solderpad Hardware License v 2.1 (the License); you may not use this file
// except in compliance with the License, or, at your option, the Apache License version 2.0. You
// may obtain a copy of the License at
//
// https://solderpad.org/licenses/SHL-2.1/
//
// Unless required by applicable law or agreed to in writing, any work distributed under the
// License is distributed on an AS IS BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND,
// either express or implied. See the License for the specific language governing permissions
// and limitations under the License.
////////////////////////////////////////////////////////////////////////////////////////////////
// load code to initalize stack, handle interrupts, terminate
.section .text.init
.global rvtest_entry_point
rvtest_entry_point:
la sp, topofstack # Initialize stack pointer (not used)
# Set up interrupts
la t0, trap_handler
csrw mtvec, t0 # Initialize MTVEC to trap_handler
csrw mideleg, zero # Don't delegate interrupts
csrw medeleg, zero # Don't delegate exceptions
csrw mie, t0 # Enable machine timer interrupt
la t0, topoftrapstack
csrw mscratch, t0 # MSCRATCH holds trap stack pointer
csrsi mstatus, 0x8 # Turn on mstatus.MIE global interrupt enable
j main # Call main function in user test program
done:
li a0, 4 # argument to finish program
ecall # system call to finish program
j self_loop # wait forever (not taken)
.align 4 # trap handlers must be aligned to multiple of 4
trap_handler:
# Load trap handler stack pointer tp
csrrw tp, mscratch, tp # swap MSCRATCH and tp
sd t0, 0(tp) # Save t0 and t1 on the stack
sd t1, -8(tp)
csrr t0, mcause # Check the cause
csrr t1, mtval # And the trap value
bgez t0, exception # if msb is clear, it is an exception
interrupt: # must be a timer interrupt
j trap_return # clean up and return
exception:
csrr t1, mepc # add 4 to MEPC to determine return Address
addi t1, t1, 4
csrw mepc, t1
li t1, 8 # is it an ecall trap?
andi t0, t0, 0xFC # if CAUSE = 8, 9, or 11
bne t0, t1, trap_return # ignore other exceptions
ecall:
li t0, 4
beq a0, t0, write_tohost # call 4: terminate program
bltu a0, t0, changeprivilege # calls 0-3: change privilege level
j trap_return # ignore other ecalls
changeprivilege:
li t0, 0x00001800 # mask off mstatus.MPP in bits 11-12
csrc mstatus, t0
andi a0, a0, 0x003 # only keep bottom two bits of argument
slli a0, a0, 11 # move into mstatus.MPP position
csrs mstatus, a0 # set mstatus.MPP with desired privilege
trap_return: # return from trap handler
ld t1, -8(tp) # restore t1 and t0
ld t0, 0(tp)
csrrw tp, mscratch, tp # restore tp
mret # return from trap
write_tohost:
la t1, tohost
li t0, 1 # 1 for success, 3 for failure
sd t0, 0(t1) # send success code
self_loop:
j self_loop # wait
.section .tohost
tohost: # write to HTIF
.dword 0
fromhost:
.dword 0
.EQU XLEN,64
begin_signature:
.fill 6*(XLEN/32),4,0xdeadbeef #
end_signature:
# Initialize stack with room for 512 bytes
.bss
.space 512
topofstack:
# And another stack for the trap handler
.bss
.space 512
topoftrapstack:
.align 4
.section .text.main

47
tests/coverage/badinstr.S Normal file
View File

@ -0,0 +1,47 @@
///////////////////////////////////////////
// badinstr.S
//
// Written: David_Harris@hmc.edu 21 March 2023
//
// Purpose: Test illegal instruction opcodes
//
// A component of the CORE-V-WALLY configurable RISC-V project.
//
// Copyright (C) 2021-23 Harvey Mudd College & Oklahoma State University
//
// SPDX-License-Identifier: Apache-2.0 WITH SHL-2.1
//
// Licensed under the Solderpad Hardware License v 2.1 (the License); you may not use this file
// except in compliance with the License, or, at your option, the Apache License version 2.0. You
// may obtain a copy of the License at
//
// https://solderpad.org/licenses/SHL-2.1/
//
// Unless required by applicable law or agreed to in writing, any work distributed under the
// License is distributed on an AS IS BASIS, WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND,
// either express or implied. See the License for the specific language governing permissions
// and limitations under the License.
////////////////////////////////////////////////////////////////////////////////////////////////
// load code to initalize stack, handle interrupts, terminate
#include "WALLY-init-lib.S"
main:
.word 0x00000033 // legal instruction
.word 0x80000033 // illegal instruction
.word 0x00000000 // illegal instruction
j done
/*
main:
# Change to user mode
li a0, 0 # a0 = 0: argument to enter user mode
ecall # System call to enter user mode
# Wait for timer interrupts
li t0, 0x1000 # loop counter start value
loop:
addi t0, t0, -1 # decrement counter
bne t0, zero, loop # and repeat until zero
*/