RiscV update with preliminary exception support, added multiplier and all the other things that didn't survive the GIT reorg

This commit is contained in:
Sven Stucki 2015-05-20 17:54:00 +02:00
parent 29012978d7
commit 72147fceed
7 changed files with 527 additions and 200 deletions

View file

@ -37,7 +37,6 @@ module controller
input logic rst_n,
input logic fetch_enable_i, // Start the decoding
output logic eoc_o, // End of computation: triggered by a special instruction
output logic core_busy_o, // Core is busy processing instructions
output logic force_nop_o,
@ -198,8 +197,6 @@ module controller
always_comb
begin
// Default values
eoc_o = 1'b0;
instr_req_o = 1'b1;
pc_mux_sel_o = `PC_INCR;
@ -265,7 +262,7 @@ module controller
take_branch_o = 1'b0;
`endif
case (ctrl_fsm_cs)
unique case (ctrl_fsm_cs)
RESET:
begin
// We were just reset and have to copy the boot address from
@ -318,6 +315,10 @@ module controller
regfile_alu_we = 1'b1;
end
`OPCODE_CUST1: begin // custom-1: Flush pipeline (e.g. wait for event)
end
//////////////////////////////////////
// _ _ _ __ __ ____ ____ //
// | | | | | \/ | _ \/ ___| //
@ -382,12 +383,6 @@ module controller
illegal_insn_o = 1'b1;
end
endcase // case (instr_rdata_i)
/*if (branch_taken_i == 1'b1) begin
pc_mux_sel_o = `PC_FROM_IMM; // TODO: Think about clever adder use
end else begin
pc_mux_sel_o = `INCR_PC;
end*/
end
/*
@ -438,26 +433,6 @@ module controller
end
`endif
`OPCODE_NOP:
begin // No Operation
// if (instr_rdata_i[25:24] == 2'b01)
// $display("%t: Executing l.nop with 0x%h.", $time, instr_rdata_i[15:0]);
// else
// $display("%t: Illegal l.nop received.", $time);
end
`OPCODE_EOC: begin // End of Computation (Custom Instruction 1)
eoc_o = 1'b1;
pc_mux_sel_o = `PC_NO_INCR;
end
`OPCODE_RFE:
begin
pc_mux_sel_o = `EXC_PC_REG; // restore PC from EPCR
restore_sr_o = 1'b1;
clear_isr_running_o = 1'b1;
end
*/
//////////////////////////////////
@ -485,8 +460,6 @@ module controller
default: begin
data_req = 1'b0;
data_we = 1'b0;
rega_used = 1'b0;
regb_used = 1'b0;
illegal_insn_o = 1'b1;
end
endcase // unique case (instr_rdata_i)
@ -521,7 +494,6 @@ module controller
default: begin
data_req = 1'b0;
regfile_we = 1'b0;
rega_used = 1'b0;
illegal_insn_o = 1'b1;
end
endcase // unique case (instr_rdata_i)
@ -621,7 +593,6 @@ module controller
*/
//////////////////////////
// _ _ _ _ //
// / \ | | | | | | //
@ -687,6 +658,9 @@ module controller
`INSTR_SRA: alu_operator = `ALU_SRA; // Shift Right Arithmetic
`INSTR_OR: alu_operator = `ALU_OR; // Or
`INSTR_AND: alu_operator = `ALU_AND; // And
`INSTR_MUL: mult_is_running = 1'b1; // Multiplication
default: begin
// synopsys translate_off
$display("%t: Illegal OP instruction: %b", $time, instr_rdata_i);
@ -998,6 +972,28 @@ module controller
// //
////////////////////////////////////////////////
*/
`OPCODE_SYSTEM: begin
unique case (instr_rdata_i) inside
`INSTR_ECALL: begin
trap_insn_o = 1'b1;
end
`INSTR_ERET: begin
pc_mux_sel_o = `PC_ERET;
restore_sr_o = 1'b1; // TODO: Check if needed
clear_isr_running_o = 1'b1; // TODO: Check if needed
end
`INSTR_WFI: begin
// flush pipeline
pipe_flush_o = 1'b1;
end
default: illegal_insn_o = 1'b1;
endcase // unique case (instr_rdata_i)
end
/*
`OPCODE_MTSPR: begin // Move To Special-Purpose Register
alu_operator = `ALU_OR;
alu_op_b_mux_sel_o = `OP_B_IMM;
@ -1117,7 +1113,6 @@ module controller
if (illegal_insn_o == 1'b1) begin
$display("%t: Illegal instruction:", $time);
prettyPrintInstruction(instr_rdata_i, id_stage.current_pc_id_i);
$stop;
end
// synopsys translate_on
@ -1234,12 +1229,8 @@ module controller
////////////////////////////////////////////////////////////////////////////////////////////
// Jump and Branch handling //
////////////////////////////////////////////////////////////////////////////////////////////
//assign force_nop_o = (jump_in_id_o != 2'b00)? 1'b1 : 1'b0;
assign force_nop_o = (jump_in_id_o != 2'b00 || jump_in_ex_i != 2'b00)? 1'b1 : 1'b0;
//assign force_nop_o = (!instr_ack_stall && (jump_in_id_o != 2'b00 || jump_in_ex_i != 2'b00))? 1'b1 : 1'b0;
//assign force_nop_o = (!stall_ex_o && jump_in_id_o == 2'b01)? 1'b1 : 1'b0;
assign drop_instruction_o = 1'b0;
////////////////////////////////////////////////////////////////////////////////////////////
// Freeze Unit. This unit controls the pipeline stages //

View file

@ -233,7 +233,6 @@ module ex_stage
// |_| |_|\___/|_____|_| |___|_| |_____|___|_____|_| \_\ //
// //
////////////////////////////////////////////////////////////////
/*
mult mult_i
(
.vector_mode_i ( vector_mode_i ),
@ -252,7 +251,6 @@ module ex_stage
.carry_o ( mult_carry_int ),
.overflow_o ( mult_overflow_int )
);
*/
///////////////////////////////////////

402
exc_controller.sv Normal file
View file

@ -0,0 +1,402 @@
////////////////////////////////////////////////////////////////////////////////
// Company: IIS @ ETHZ - Federal Institute of Technology //
// //
// Engineer: Andreas Traber - atraber@student.ethz.ch //
// //
// Additional contributions by: //
// //
// //
// //
// Create Date: 20/01/2015 //
// Design Name: Pipelined OpenRISC Processor //
// Module Name: exc_controller.sv //
// Project Name: OR10N //
// Language: SystemVerilog //
// //
// Description: Exception Controller of the pipelined processor //
// //
// //
// Revision: //
// Revision v0.1 - File Created //
// //
// //
// //
////////////////////////////////////////////////////////////////////////////////
`include "defines.sv"
module exc_controller
(
input logic clk,
input logic rst_n,
input logic fetch_enable_i,
// to IF stage
output logic exc_pc_sel_o, // influences next PC, if set exception PC is used
output logic [1:0] exc_pc_mux_o, // Selector in the Fetch stage to select the rigth exception PC
output logic force_nop_o, // Force a Nop (Bubble) in the Fetch stage
// hwloop signals
output logic hwloop_enable_o, // '1' if pc is valid (interrupt related signal)
// Interrupt signals
input logic irq_i, // level-triggered IR line
input logic irq_nm_i, // level-triggered IR line for non-maskable IRQ
input logic irq_enable_i, // global interrupt enable
output logic irq_present_o, // tells the controller to start fetching instructions if asleep
// SPR
output logic save_pc_if_o, // saves current_pc_if before entering interrupt routine
output logic save_pc_id_o, // saves current_pc_id before entering interrupt routine
output logic save_sr_o, // saves status register
output logic set_dsx_o, // set delay slot flag
// Controller
input logic core_busy_i, // Is the controller currently in the IDLE state?
input logic [1:0] jump_in_id_i, // jump instruction in ID stage
input logic [1:0] jump_in_ex_i, // jump instruction in EX stage
input logic stall_id_i, // Stall ID stage
input logic illegal_insn_i, // Illegal instruction encountered in ID stage
input logic trap_insn_i, // Trap instruction encountered in ID stage
input logic pipe_flush_i, // pipe flush requested by controller
output logic pc_valid_o, // is the PC in the IF stage currently valid?
input logic clear_isr_running_i, // exit ISR routine
// Debug Unit Signals
input logic dbg_flush_pipe_i, // Pipe flush requested
output logic pipe_flushed_o, // Pipe is flushed
input logic dbg_st_en_i, // Single-step trace mode enabled
input logic [1:0] dbg_dsr_i, // Debug Stop Register
input logic dbg_stall_i, // Pipeline stall is requested
input logic dbg_set_npc_i, // Change PC to value from debug unit
output logic dbg_trap_o // Software Trap in ID (l.trap)
);
// Exception unit state encoding
enum logic [2:0] { Idle, SingleStep, NopDelay, NopDelayIR, NopID, NopEX, NopWB} exc_fsm_cs, exc_fsm_ns;
enum logic [2:0] { ExcNone, ExcST, ExcIR, ExcTrap, ExcFlush, ExcDbgFlush, ExcIllegalInsn } exc_reason_p, exc_reason_n, exc_reason;
// Registers
logic exc_running_p, exc_running_n;
logic clear_exc_reason;
// disable hardware loops when nops are inserted or the controller is not active
assign hwloop_enable_o = (~force_nop_o) | (~core_busy_i);
/////////////////////////////////////////////
// ____ _ //
// | _ \ ___ ___ ___ __| | ___ _ __ //
// | | | |/ _ \/ __/ _ \ / _` |/ _ \ '__| //
// | |_| | __/ (_| (_) | (_| | __/ | //
// |____/ \___|\___\___/ \__,_|\___|_| //
// //
/////////////////////////////////////////////
// a trap towards the debug unit is generated when one of the
// following conditions are true:
// - l.trap instruction encountered
// - single-stepping mode enabled (after one instruction is executed)
// - illegal instruction exception and IIE bit is set
// - IRQ and INTE bit is set and no exception is currently running
assign dbg_trap_o = trap_insn_i || dbg_st_en_i || (illegal_insn_i & dbg_dsr_i[`DSR_IIE]) || (irq_present_o & dbg_dsr_i[`DSR_INTE] & (~exc_running_p));
assign irq_present_o = (irq_i || irq_nm_i) & irq_enable_i;
// Decoder for exc_reason signal
// this signal tells the exception controller which is the exception
// with highest priority at the moment
// The decoder also takes care that no nested exceptions are performed
always_comb
begin
exc_reason = ExcNone;
if (dbg_st_en_i == 1'b1)
begin
// Single-step trace mode
exc_reason = ExcST;
end
else if ((trap_insn_i == 1'b1) || (dbg_flush_pipe_i == 1'b1))
begin
// flushing pipeline because of l.trap instruction
exc_reason = ExcTrap;
end
else if (illegal_insn_i == 1'b1)
begin
// if the IIE bit in the Debug Stop Register is set, we transfer
// the control to the debug interface
// otherwise we jump to the interrupt handler, if we are not
// already in an interrupt handler
if (dbg_dsr_i[`DSR_IIE] == 1'b1)
exc_reason = ExcTrap;
else if (exc_running_p == 1'b0)
exc_reason = ExcIllegalInsn;
end
else if ((irq_present_o == 1'b1) && (exc_running_p == 1'b0))
begin
// an interrupt is present, flush pipeline, execute pending delay slots
// and then call the interrupt handler
// or if the INTE bit is set, transfer the control to the debug interface
if (dbg_dsr_i[`DSR_INTE] == 1'b1)
exc_reason = ExcTrap;
else
exc_reason = ExcIR;
end
else if(pipe_flush_i == 1'b1)
begin
// flushing pipeline because of l.psync
exc_reason = ExcFlush;
end
else if (clear_isr_running_i == 1'b1)
begin
// if we receive an l.rfe instruction when we are not in an
// exception handler, we jump to the illegal instruction handler
if (exc_running_p == 1'b1)
begin
// synopsys translate_off
$display("%t: Exiting exception routine.", $time);
// synopsys translate_on
// the CPU should go back to sleep
if(fetch_enable_i == 1'b0)
exc_reason = ExcFlush;
end
else
exc_reason = ExcIllegalInsn;
end
end
//////////////////////////////////////////////////////////////////////
// _____ _ _ ____ _ _ //
// | ____|_ _____ ___ _ __ | |_(_) ___ _ __ / ___| |_ _ __| | //
// | _| \ \/ / __/ _ \ '_ \| __| |/ _ \| '_ \ | | | __| '__| | //
// | |___ > < (_| __/ |_) | |_| | (_) | | | | | |___| |_| | | | //
// |_____/_/\_\___\___| .__/ \__|_|\___/|_| |_| \____|\__|_| |_| //
// |_| //
//////////////////////////////////////////////////////////////////////
// exception control FSM
always_comb begin
exc_fsm_ns = exc_fsm_cs;
exc_reason_n = exc_reason_p;
exc_running_n = exc_running_p;
clear_exc_reason = 1'b0;
save_pc_if_o = 1'b0;
save_pc_id_o = 1'b0;
save_sr_o = 1'b0;
set_dsx_o = 1'b0;
pipe_flushed_o = 1'b0;
force_nop_o = 1'b0;
pc_valid_o = 1'b1;
exc_pc_sel_o = 1'b0;
exc_pc_mux_o = `EXC_PC_NO_INCR;
case (exc_fsm_cs)
Idle: begin
exc_reason_n = exc_reason;
unique case (exc_reason_n)
// A flush of the pipeline was requested by the debug
// unit, an l.psync instruction or an l.rfe instruction
// execute pending delay slot (l.psync won't have one),
// flush the pipeline and stop
ExcDbgFlush, ExcFlush: begin
if (jump_in_id_i == 2'b00)
begin // no delay slot
force_nop_o = 1'b1;
exc_pc_sel_o = 1'b1;
exc_pc_mux_o = `EXC_PC_NO_INCR;
pc_valid_o = 1'b0;
exc_fsm_ns = NopID;
end
else
begin // delay slot
exc_fsm_ns = NopDelay;
end
end
// an IRQ is present, execute pending delay slots and jump
// to the ISR without flushing the pipeline
ExcIR: begin
if (jump_in_id_i == 2'b00)
begin // no delay slot
// synopsys translate_off
$display("%t: Entering exception routine.", $time);
// synopsys translate_on
force_nop_o = 1'b1;
exc_pc_sel_o = 1'b1;
save_pc_if_o = 1'b1; // save current PC
save_sr_o = 1'b1; // save Supervision Register
if (irq_nm_i == 1'b1) // emergency IRQ has higher priority
exc_pc_mux_o = `EXC_PC_IRQ_NM;
else // irq_i == 1'b1
exc_pc_mux_o = `EXC_PC_IRQ;
exc_running_n = 1'b1;
clear_exc_reason = 1'b1;
exc_fsm_ns = Idle;
end
else // delay slot
begin
exc_fsm_ns = NopDelayIR;
end
end
// Illegal instruction encountered, we directly jump to
// the ISR without flushing the pipeline
ExcIllegalInsn: begin
// synopsys translate_off
$display("%t: Entering exception routine.", $time);
// synopsys translate_on
force_nop_o = 1'b1;
exc_pc_sel_o = 1'b1;
exc_pc_mux_o = `EXC_PC_ILLINSN;
save_pc_id_o = 1'b1; // save current PC
save_sr_o = 1'b1; // save Supervision Register
exc_running_n = 1'b1;
clear_exc_reason = 1'b1;
exc_fsm_ns = Idle;
end
// flushing pipeline because of l.trap instruction
// we do not wait for delay slots, but we set a flag if we are in one
ExcTrap: begin
force_nop_o = 1'b1;
exc_pc_sel_o = 1'b1;
exc_pc_mux_o = `EXC_PC_IRQ;
pc_valid_o = 1'b0;
if (jump_in_ex_i == 2'b10)
set_dsx_o = 1'b1; // set delay slot flag if we are in a delay slot
exc_fsm_ns = NopID;
end
// Single-step Trace Mode
// Flush the pipeline after one instruction was executed,
// if we are in a delay slot, wait for the delay slot to
// be executed
ExcST: begin
exc_fsm_ns = SingleStep;
end
default:; // Nothing
endcase
end // case: Idle
// Execute exactly one instruction before stalling again
SingleStep:
begin
if (jump_in_id_i == 2'b00)
begin // no delay slot
force_nop_o = 1'b1;
exc_pc_sel_o = 1'b1;
exc_pc_mux_o = `EXC_PC_NO_INCR;
pc_valid_o = 1'b0;
exc_fsm_ns = NopID;
end
else
begin // delay slot
exc_fsm_ns = NopDelay;
end
end
// Execute delay slot for IR
NopDelayIR:
begin
// synopsys translate_off
$display("%t: Entering exception routine.", $time);
// synopsys translate_on
force_nop_o = 1'b1;
exc_pc_sel_o = 1'b1;
save_pc_if_o = 1'b1; // save current PC
save_sr_o = 1'b1; // save Supervision Register
if (irq_nm_i == 1'b1) // emergency IRQ has higher priority
exc_pc_mux_o = `EXC_PC_IRQ_NM;
else // irq_i == 1'b1
exc_pc_mux_o = `EXC_PC_IRQ;
exc_running_n = 1'b1;
clear_exc_reason = 1'b1;
exc_fsm_ns = Idle;
end
// Execute delay slot, start to force NOPs for new instructions
NopDelay:
begin
force_nop_o = 1'b1;
exc_pc_sel_o = 1'b1;
exc_pc_mux_o = `EXC_PC_NO_INCR;
pc_valid_o = 1'b0;
exc_fsm_ns = NopID;
end
// First NOP is in ID stage
NopID:
begin
force_nop_o = 1'b1;
exc_pc_sel_o = 1'b1;
exc_pc_mux_o = `EXC_PC_NO_INCR;
pc_valid_o = 1'b0;
exc_fsm_ns = NopEX;
end
// First NOP is in EX stage
NopEX:
begin
force_nop_o = 1'b1;
pc_valid_o = 1'b0;
exc_pc_sel_o = 1'b1;
exc_pc_mux_o = `EXC_PC_NO_INCR;
exc_fsm_ns = NopWB;
end
// First NOP is in WB stage
// Pipeline is flushed now
NopWB: begin
exc_pc_sel_o = 1'b1;
exc_pc_mux_o = `EXC_PC_NO_INCR;
pipe_flushed_o = 1'b1;
pc_valid_o = 1'b0;
force_nop_o = 1'b1;
clear_exc_reason = 1'b1;
exc_fsm_ns = Idle;
end
default: exc_fsm_ns = Idle;
endcase // case (exc_fsm_cs)
end
always_ff @(posedge clk , negedge rst_n)
begin : UPDATE_REGS
if ( rst_n == 1'b0 )
begin
exc_fsm_cs <= Idle;
exc_running_p <= 1'b0;
exc_reason_p <= ExcNone;
end
else if (stall_id_i == 1'b0)
begin
exc_fsm_cs <= exc_fsm_ns;
exc_running_p <= (clear_isr_running_i == 1'b1) ? 1'b0 : exc_running_n;
exc_reason_p <= (clear_exc_reason == 1'b1) ? ExcNone : exc_reason_n;
end
end
endmodule // exc_controller

View file

@ -51,11 +51,9 @@ module id_stage
// Jumps and branches
output logic [1:0] jump_in_id_o,
//input logic [1:0] jump_in_ex_i,
output logic [1:0] jump_in_ex_o,
// IF and ID stage signals
//output logic [31:0] pc_from_immediate_o, // TODO: remove
output logic [2:0] pc_mux_sel_o,
output logic pc_mux_boot_o,
@ -86,8 +84,6 @@ module id_stage
output logic [1:0] alu_cmp_mode_ex_o,
output logic [1:0] alu_vec_ext_ex_o,
output logic eoc_ex_o,
output logic mult_is_running_ex_o, // TODO: Rename (-> mult enable ?)
output logic [1:0] mult_sel_subword_ex_o,
output logic [1:0] mult_signed_mode_ex_o,
@ -192,9 +188,9 @@ module id_stage
logic exc_pc_sel;
logic [2:0] pc_mux_sel_int; // selects next PC in if stage
//logic pc_from_immediate_mux_sel = 1'b0; // TODO: FIXME (remove)
logic force_nop_controller;
logic force_nop_exc;
logic irq_present;
@ -244,8 +240,6 @@ module id_stage
logic mult_use_carry; // Enables carry in for the MAC
logic mult_mac_en; // Enables the use of the accumulator
logic eoc; // End of computation generated from the controller
// Register Write Control
logic regfile_wdata_mux_sel;
logic regfile_we_id;
@ -292,11 +286,8 @@ module id_stage
logic [31:0] operand_c;
// TODO: FIXME temporary assignments while not everything is implemented (e.g. exceptions)
assign exc_pc_sel = 1'b0;
assign pc_valid = 1'b1;
assign force_nop_o = force_nop_controller | force_nop_exc;
assign pc_mux_sel_o = (exc_pc_sel == 1'b1) ? `PC_EXCEPTION : pc_mux_sel_int;
// immediate extraction and sign extension
@ -340,17 +331,6 @@ module id_stage
// |___/ //
///////////////////////////////////////////////////////////////////////////////////////
// PC offset for `PC_FROM_IMM PC mux
//assign pc_from_immediate_o = imm_uj_type; // riscv no longer used
//always_comb
//begin : pc_from_immediate_mux
// case (pc_from_immediate_mux_sel)
// 1'b0: pc_from_immediate_o = imm_uj_type; // JAL
// 1'b1: pc_from_immediate_o = imm_i_type; // JALR
// endcase // case (pc_from_immediate_mux_sel)
//end
//assign pc_from_immediate_o = imm_sb_type; // TODO: Remove/Replace?
// PC Mux
always_comb
begin : alu_pc_mux
@ -574,7 +554,6 @@ module id_stage
.clk ( clk ),
.rst_n ( rst_n ),
.fetch_enable_i ( fetch_enable_i ),
.eoc_o ( eoc ),
.core_busy_o ( core_busy_o ),
.force_nop_o ( force_nop_controller ),
@ -702,9 +681,6 @@ module id_stage
// //
///////////////////////////////////////////////////////////////////////
assign force_nop_o = force_nop_controller;
/*
exc_controller exc_controller_i
(
.clk ( clk ),
@ -715,7 +691,7 @@ module id_stage
// to IF stage
.exc_pc_sel_o ( exc_pc_sel ),
.exc_pc_mux_o ( exc_pc_mux_o ),
.force_nop_o ( force_nop_o ),
.force_nop_o ( force_nop_exc ),
// hwloop signals
.hwloop_enable_o ( hwloop_enable ),
@ -752,7 +728,6 @@ module id_stage
.dbg_set_npc_i ( dbg_set_npc_i ),
.dbg_trap_o ( dbg_trap_o )
);
*/
//////////////////////////////////////////////////////////////////////////
@ -848,8 +823,6 @@ module id_stage
jump_in_ex <= 2'b0;
eoc_ex_o <= 1'b0;
`ifdef TCDM_ADDR_PRECAL
alu_adder_o <= '0;
`endif
@ -923,8 +896,6 @@ module id_stage
jump_in_ex <= jump_in_id_o;
eoc_ex_o <= eoc;
`ifdef TCDM_ADDR_PRECAL
alu_adder_o <= alu_operand_a + alu_operand_b;
`endif

View file

@ -60,6 +60,7 @@ module if_stage
// jump and branch target and decision
input logic [31:0] jump_target_i, // jump target
input logic [1:0] jump_in_id_i,
input logic [1:0] jump_in_ex_i, // jump in EX -> get PC from jump target (could also be branch)
input logic branch_decision_i,
@ -84,36 +85,17 @@ module if_stage
// Address to fetch the instruction
assign instr_addr_o = next_pc;
// Next PC Selection: pc_mux_sel_i comes from id_stage.controller
/*always_comb
begin : PC_MUX
case (pc_mux_sel_i)
`INCR_PC: begin next_pc = current_pc_if_o + 32'd4; end // PC is incremented and points the next instruction
`NO_INCR: begin next_pc = current_pc_if_o; end // PC is not incremented
//`PC_FROM_REGFILE: begin next_pc = pc_from_regfile_i; end // PC is taken from the regfile
//`PC_FROM_ALU: begin next_pc = pc_from_alu_i; end // use calculated jump target from ALU
`PC_EXCEPTION: begin next_pc = exc_pc; end // PC that points to the exception
`EXC_PC_REG: begin next_pc = exception_pc_reg_i; end // restore the PC when exiting from interr/ecpetions
`HWLOOP_ADDR: begin next_pc = pc_from_hwloop_i; end // PC is taken from hwloop start addr
`ifdef BRANCH_PREDICTION
`PC_BRANCH_PRED: begin next_pc = correct_branch; end // take pc from branch prediction
`endif
default: begin next_pc = current_pc_if_o + 32'd4; end
endcase //~case (pc_mux_sel_i)
end */
// Exception PC selection
always_comb
begin : EXC_PC_MUX
case (exc_pc_mux_i)
`EXC_PC_IRQ: begin exc_pc = {boot_addr_i[31:8], `EXC_IRQ }; end
`EXC_PC_IRQ_NM: begin exc_pc = {boot_addr_i[31:8], `EXC_IRQ_NM }; end
`EXC_PC_ILLINSN: begin exc_pc = {boot_addr_i[31:8], `EXC_ILLINSN}; end
`EXC_PC_NO_INCR: begin exc_pc = current_pc_if_o; end
`EXC_PC_NO_INCR: begin exc_pc = current_pc_if_o; end
`EXC_PC_ILLINSN: begin exc_pc = {boot_addr_i[31:5], `EXC_OFF_ILLINSN }; end
`EXC_PC_IRQ: begin exc_pc = {boot_addr_i[31:5], `EXC_OFF_IRQ }; end
`EXC_PC_IRQ_NM: begin exc_pc = {boot_addr_i[31:5], `EXC_OFF_IRQ_NM }; end
endcase //~case (exc_pc_mux_i)
end
// PC selection and force NOP logic
always_comb
begin
@ -124,30 +106,36 @@ module if_stage
`PC_INCR: next_pc = current_pc_if_o + 32'd4; // PC is incremented and points the next instruction
`PC_NO_INCR: next_pc = current_pc_if_o; // PC is not incremented
`PC_EXCEPTION: next_pc = exc_pc; // PC that points to the exception
`EXC_PC_REG: next_pc = exception_pc_reg_i; // restore the PC when exiting from interr/ecpetions
`PC_ERET: next_pc = exception_pc_reg_i; // restore the PC when returning from IRQ/exception
`HWLOOP_ADDR: next_pc = pc_from_hwloop_i; // PC is taken from hwloop start addr
default:
begin
next_pc = current_pc_if_o;
// synopsis translate off
// synopsys translate_off
$display("%t: Illegal pc_mux_sel value (%0d)!", $time, pc_mux_sel_i);
// synopsis translate on
// synopsys translate_on
end
endcase // unique case (pc_mux_sel_i)
// if force NOP, do not increase PC
if (force_nop_i == 1'b1) begin
instr_rdata_int = { 25'b0, `OPCODE_OPIMM }; // addi x0 = x0 + 0
end
// freeze PC if jump/branch in pipeline
if (jump_in_id_i != 2'b00) begin
next_pc = current_pc_if_o;
end
if (jump_in_ex_i == 2'b01) begin
// jump handling
next_pc = jump_target_i;
end else if (jump_in_ex_i == 2'b10) begin
// branch handling
if (branch_decision_i == 1'b1)
next_pc = jump_target_i;
else
next_pc = current_pc_if_o;// + 32'd4; // TODO: Check if merged with previous adder (from PC mux)
next_pc = current_pc_if_o;
end
end
@ -166,8 +154,8 @@ module if_stage
begin : DEASSERT_RESET
if ( pc_mux_boot_i == 1'b1 )
begin
// set PC to boot address if we were just reset
current_pc_if_o <= boot_addr_i;
// set PC to reset vector
current_pc_if_o <= {boot_addr_i[31:5], `EXC_OFF_RST};
end
else if ( dbg_set_npc == 1'b1 )
begin

View file

@ -40,50 +40,6 @@
// |_| //
////////////////////////////////////////////////
/*
`define OPCODE_J 6'h00
`define OPCODE_JAL 6'h01
`define OPCODE_HWLOOP 6'h02
`define OPCODE_BNF 6'h03
`define OPCODE_BF 6'h04
`define OPCODE_NOP 6'h05
`define OPCODE_MOVHI 6'h06 // also used for l.macrc
`define OPCODE_SYNC 6'h08 // also used for l.trap
`define OPCODE_RFE 6'h09
`define OPCODE_VEC 6'h0a // vectorial instructions
`define OPCODE_VCMP 6'h0b // vectorial compare instructions
`define OPCODE_JR 6'h11
`define OPCODE_JALR 6'h12
`define OPCODE_MACI 6'h13
`define OPCODE_EOC 6'h1c // l.eoc = l.cust1
`define OPCODE_STPOST 6'h14 // ST post-increment
`define OPCODE_STPRE 6'h15 // ST pre-increment
`define OPCODE_LDPOST 6'h16 // LD post-increment
`define OPCODE_LDPRE 6'h17 // LD pre-increment
`define OPCODE_LWZ 6'h21
`define OPCODE_LWS 6'h22
`define OPCODE_LBZ 6'h23
`define OPCODE_LBS 6'h24
`define OPCODE_LHZ 6'h25
`define OPCODE_LHS 6'h26
`define OPCODE_ADDI 6'h27
`define OPCODE_ADDIC 6'h28
`define OPCODE_ANDI 6'h29
`define OPCODE_ORI 6'h2a
`define OPCODE_XORI 6'h2b
`define OPCODE_MULI 6'h2c
`define OPCODE_MFSPR 6'h2d
`define OPCODE_SHIFT 6'h2e
`define OPCODE_SFI 6'h2f
`define OPCODE_MTSPR 6'h30
`define OPCODE_MAC 6'h31
`define OPCODE_SW 6'h35
`define OPCODE_SB 6'h36
`define OPCODE_SH 6'h37
`define OPCODE_ALU 6'h38
`define OPCODE_SF 6'h39
*/
`define OPCODE_SYSTEM 7'h73
`define OPCODE_FENCE 7'h0f
`define OPCODE_OP 7'h33
@ -96,6 +52,7 @@
`define OPCODE_AUIPC 7'h17
`define OPCODE_LUI 7'h37
`define OPCODE_CUST0 7'h0b
`define OPCODE_CUST1 7'h2b
`define INSTR_CUSTOM0 { {25 {1'b?}}, `OPCODE_CUST0 }
`define INSTR_LUI { {25 {1'b?}}, `OPCODE_LUI }
@ -144,8 +101,10 @@
`define INSTR_FENCE { 4'b0000, {8 {1'b?}}, {13 {1'b0}}, `OPCODE_FENCE }
`define INSTR_FENCEI { {17 {1'b0}}, 3'b001, {5 {1'b0}}, `OPCODE_FENCE }
// SYSTEM
`define INSTR_SCALL { {11 {1'b0}}, 1'b0, {13 {1'b0}}, `OPCODE_SYSTEM }
`define INSTR_SBREAK { {11 {1'b0}}, 1'b1, {13 {1'b0}}, `OPCODE_SYSTEM }
`define INSTR_ECALL { 12'b000000000000, {13 {1'b0}}, `OPCODE_SYSTEM }
`define INSTR_EBREAK { 12'b000000000001, {13 {1'b0}}, `OPCODE_SYSTEM }
`define INSTR_ERET { 12'b000100000000, {13 {1'b0}}, `OPCODE_SYSTEM }
`define INSTR_WFI { 12'b000100000010, {13 {1'b0}}, `OPCODE_SYSTEM }
`define INSTR_RDCYCLE { 5'b11000, {5 {1'b0}}, 2'b00, {5 {1'b0}}, 3'b010, {5 {1'b?}}, `OPCODE_SYSTEM }
`define INSTR_RDCYCLEH { 5'b11001, {5 {1'b0}}, 2'b00, {5 {1'b0}}, 3'b010, {5 {1'b?}}, `OPCODE_SYSTEM }
`define INSTR_RDTIME { 5'b11000, {5 {1'b0}}, 2'b01, {5 {1'b0}}, 3'b010, {5 {1'b?}}, `OPCODE_SYSTEM }
@ -155,10 +114,10 @@
// RV32M
`define INSTR_MUL { 7'b0000001, {10 {1'b?}}, 3'b000, {5 {1'b?}}, `OPCODE_OP }
/* not implemented
`define INSTR_MULH { 7'b0000001, {10 {1'b?}}, 3'b001, {5 {1'b?}}, `OPCODE_OP }
`define INSTR_MULHSU { 7'b0000001, {10 {1'b?}}, 3'b010, {5 {1'b?}}, `OPCODE_OP }
`define INSTR_MULHU { 7'b0000001, {10 {1'b?}}, 3'b011, {5 {1'b?}}, `OPCODE_OP }
/* not implemented
`define INSTR_DIV { 7'b0000001, {10 {1'b?}}, 3'b100, {5 {1'b?}}, `OPCODE_OP }
`define INSTR_DIVU { 7'b0000001, {10 {1'b?}}, 3'b101, {5 {1'b?}}, `OPCODE_OP }
`define INSTR_REM { 7'b0000001, {10 {1'b?}}, 3'b110, {5 {1'b?}}, `OPCODE_OP }
@ -171,7 +130,7 @@
`define REG_D 11:07
// synopsis translate off
// synopsys translate_off
`define TRACE_EXECUTION
function void prettyPrintInstruction(input [31:0] instr, input [31:0] pc);
@ -199,7 +158,7 @@ function void prettyPrintInstruction(input [31:0] instr, input [31:0] pc);
$display();
end
endfunction // prettyPrintInstruction
// synopsis translate on
// synopsys translate_on
@ -361,7 +320,7 @@ endfunction // prettyPrintInstruction
`define PC_INCR 3'b000
`define PC_NO_INCR 3'b001
`define PC_EXCEPTION 3'b100
`define EXC_PC_REG 3'b101
`define PC_ERET 3'b101
`define HWLOOP_ADDR 3'b110
`define PC_BRANCH_PRED 3'b111
@ -372,12 +331,16 @@ endfunction // prettyPrintInstruction
`define EXC_PC_IRQ_NM 2'b11
// Exceptions offsets
// It is assumed that the lower 8 bits are enough for all exception
// offsets, so the upper 24 bits of the boot address are used and the
// lower 8 bits of the exception offset
`define EXC_ILLINSN 8'h30
`define EXC_IRQ 8'h38
`define EXC_IRQ_NM 8'h70
// target address = {boot_addr[31:5], EXC_OFF} (boot_addr must be 32 BYTE aligned!)
`define EXC_OFF_RST 5'h10
`define EXC_OFF_IRQ 5'h00
`define EXC_OFF_IRQ_NM 5'h04
`define EXC_OFF_ILLINSN 5'h08
// unused 5'h0c
// Exception causes
`define EXC_CAUSE_ECALL {1'b0, 4'd11};
`define EXC_CAUSE_EBREAK {1'b0, 4'd03};
// Hardware loops addon

View file

@ -127,10 +127,6 @@ module riscv_core
logic carry_ex;
logic overflow_ex;
// End of Computation
logic eoc_ex;
logic eoc_wb;
// Multiplier Control
logic mult_is_running_ex;
logic [1:0] mult_sel_subword_ex;
@ -248,6 +244,9 @@ module riscv_core
`endif
// TODO: Remove from cluster
assign eoc_o = 1'b0;
//////////////////////////////////////////////////
// ___ _____ ____ _____ _ ____ _____ //
@ -279,7 +278,6 @@ module riscv_core
.force_nop_i ( force_nop_id ), // select incoming instr or NOP
.exception_pc_reg_i ( epcr ), // Exception PC register
.pc_from_regfile_i ( pc_from_regfile_id ), // pc from reg file
//.pc_from_immediate_i ( pc_from_immediate_id ), // pc from immediate
.pc_from_hwloop_i ( hwloop_targ_addr ), // pc from hwloop start address
.pc_mux_sel_i ( pc_mux_sel_id ), // sel for pc multiplexer
.pc_mux_boot_i ( pc_mux_boot ), // load boot address as PC
@ -290,6 +288,7 @@ module riscv_core
.dbg_set_npc ( dbg_set_npc ),
// Jump and branch target and decision
.jump_in_id_i ( jump_in_id ),
.jump_in_ex_i ( jump_in_ex ),
.branch_decision_i ( branch_decision ),
.jump_target_i ( jump_target ),
@ -390,8 +389,6 @@ module riscv_core
.alu_cmp_mode_ex_o ( alu_cmp_mode_ex ), // from ID to EX stage
.alu_vec_ext_ex_o ( alu_vec_ext_ex ), // from ID to EX stage
.eoc_ex_o ( eoc_ex ),
.mult_is_running_ex_o ( mult_is_running_ex ), // from ID to EX stage
.mult_sel_subword_ex_o ( mult_sel_subword_ex ), // from ID to EX stage
.mult_signed_mode_ex_o ( mult_signed_mode_ex ), // from ID to EX stage
@ -541,7 +538,6 @@ module riscv_core
.set_overflow_i ( set_overflow_ex ),
.set_carry_i ( set_carry_ex ),
.eoc_i ( eoc_ex ),
.regfile_rb_data_i ( regfile_rb_data_ex ),
.sp_we_i ( sp_we_ex ),
@ -560,7 +556,6 @@ module riscv_core
.hwloop_cnt_data_o ( hwloop_cnt_data ),
.sp_we_wb_o ( sp_we_wb ),
.eoc_o ( eoc_wb ),
// From ID: Jump and Branch detection
.jump_in_id_i ( jump_in_id ),
@ -602,10 +597,7 @@ module riscv_core
.lsu_data_reg_i ( lsu_data_reg ),
// Mux output
.regfile_wdata_o ( regfile_wdata ),
.wdata_reg_o ( wdata_reg_fw_id ),
.eoc_i ( eoc_wb ),
.eoc_o ( eoc_o )
.wdata_reg_o ( wdata_reg_fw_id )
);
@ -748,9 +740,6 @@ module riscv_core
);
*/
/////////////////////////////////////////////////////////////
// ____ _____ ____ _ _ ____ _ _ _ _ ___ _____ //
// | _ \| ____| __ )| | | |/ ___| | | | | \ | |_ _|_ _| //
@ -791,10 +780,14 @@ module riscv_core
.regfile_rdata_i ( dbg_rdata )
);
*/
assign dbg_reg_mux = 0;
assign dbg_stall = 0;
// Execution trace generation
// synopsis translate off
// synopsys translate_off
`ifdef TRACE_EXECUTION
integer f;
string fn;
@ -802,6 +795,8 @@ module riscv_core
logic [31:0] pc;
logic [5:0] rd, rs1, rs2;
logic [31:0] rs1_value, rs2_value;
logic [31:0] imm;
string mnemonic;
// open/close output file for writing
initial
@ -820,10 +815,12 @@ module riscv_core
// log execution
always @(posedge clk)
begin
#1
// get current PC and instruction
instr = id_stage_i.instr_rdata_i[31:0];
pc = id_stage_i.current_pc_id_i;
// get register values
rd = instr[`REG_D];
rs1 = instr[`REG_S1];
@ -831,12 +828,17 @@ module riscv_core
rs2 = instr[`REG_S2];
rs2_value = id_stage_i.operand_b_fw_id; //r[rs2];
if (fetch_enable_i == 1'b1 && id_stage_i.stall_id_o == 1'b0 && id_stage_i.controller_i.ctrl_fsm_cs == id_stage_i.controller_i.DECODE)
if (id_stage_i.stall_id_o == 1'b0 && id_stage_i.controller_i.ctrl_fsm_cs == id_stage_i.controller_i.DECODE)
begin
//$display("%h", instr);
mnemonic = "";
imm = 0;
$fwrite(f, "%t:\t0x%h\t0x%h\t", $time, pc, instr);
casex (instr)
`INSTR_CUSTOM0: $fdisplay(f, "CUSTOM0");
// Aliases
32'h00_00_00_13: printMnemonic("NOP");
// Regular opcodes
`INSTR_CUSTOM0: printMnemonic("CUSTOM0");
`INSTR_LUI: printIInstr("LUI");
`INSTR_AUIPC: printIInstr("AUIPC");
`INSTR_JAL: printUJInstr("JAL");
@ -880,11 +882,12 @@ module riscv_core
`INSTR_OR: printRInstr("OR");
`INSTR_AND: printRInstr("AND");
// FENCE
`INSTR_FENCE: $fdisplay(f, "FENCE");
`INSTR_FENCEI: $fdisplay(f, "FENCEI");
`INSTR_FENCE: printMnemonic("FENCE");
`INSTR_FENCEI: printMnemonic("FENCEI");
// SYSTEM
`INSTR_SCALL: $fdisplay(f, "SCALL");
`INSTR_SBREAK: $fdisplay(f, "SBREAK");
`INSTR_ECALL: printMnemonic("ECALL");
`INSTR_EBREAK: printMnemonic("EBREAK");
`INSTR_ERET: printMnemonic("ERET");
`INSTR_RDCYCLE: printRDInstr("RDCYCLE");
`INSTR_RDCYCLEH: printRDInstr("RDCYCLEH");
`INSTR_RDTIME: printRDInstr("RDTIME");
@ -893,64 +896,75 @@ module riscv_core
`INSTR_RDINSTRETH: printRDInstr("RDINSTRETH");
// RV32M
`INSTR_MUL: printRInstr("MUL");
/*
`INSTR_MULH: printRInstr("MULH");
`INSTR_MULHSU: printRInstr("MULHSU");
`INSTR_MULHU: printRInstr("MULHU");
default: $fdisplay(f, "Unknown instruction");
*/
default: printMnemonic("Unknown instruction");
endcase // unique case (instr)
end
end
end // always @ (posedge clk)
function void printMnemonic(input string mnemonic);
begin
riscv_core.mnemonic = mnemonic;
$fdisplay(f, "%s", mnemonic);
end
endfunction // printMnemonic
function void printRInstr(input string mnemonic);
begin
riscv_core.mnemonic = mnemonic;
$fdisplay(f, "%s\tx%0d, x%d (0x%h), x%0d (0x%h)", mnemonic,
rd, rs1, rs1_value, rs2, rs2_value);
end
endfunction // printRInstr
function void printIInstr(input string mnemonic);
logic [31:0] i_imm;
begin
i_imm = { {20 {instr[31]}}, instr[31:20] };
riscv_core.mnemonic = mnemonic;
imm = id_stage_i.imm_i_type;
$fdisplay(f, "%s\tx%0d, x%0d (0x%h), 0x%0d (imm)", mnemonic,
rd, rs1, rs1_value, i_imm);
rd, rs1, rs1_value, imm);
end
endfunction // printIInstr
function void printSInstr(input string mnemonic);
logic [31:0] s_imm;
begin
s_imm = { {20 {instr[31]}}, instr[31:25], instr[11:7] };
$fdisplay(f, "%s\tx%0d (0x%h), x%0d (0x%h), 0x%h (imm)", mnemonic,
rs1, rs1_value, rs2, rs2_value, s_imm);
riscv_core.mnemonic = mnemonic;
imm = id_stage_i.imm_s_type;
$fdisplay(f, "%s\tx%0d (0x%h), x%0d (0x%h), 0x%h (imm) (-> 0x%h)", mnemonic,
rs1, rs1_value, rs2, rs2_value, imm, imm+rs1_value);
end
endfunction // printSInstr
function void printSBInstr(input string mnemonic);
logic [31:0] sb_imm;
begin
sb_imm = { {20 {instr[31]}}, instr[31], instr[7], instr[30:25], instr[11:8] };
riscv_core.mnemonic = mnemonic;
imm = id_stage_i.imm_sb_type;
$fdisplay(f, "%s\tx%0d (0x%h), x%0d (0x%h), 0x%h (-> 0x%h)", mnemonic,
rs1, rs1_value, rs2, rs2_value, sb_imm, sb_imm+pc);
rs1, rs1_value, rs2, rs2_value, imm, imm+pc);
end
endfunction // printSBInstr
function void printUJInstr(input string mnemonic);
logic [31:0] uj_imm;
begin
uj_imm = { {20 {instr[31]}}, instr[19:12], instr[20], instr[30:21], 1'b0 };
$fdisplay(f, "%s\tx%0d, 0x%h (-> 0x%h)", mnemonic, rd, uj_imm, uj_imm+pc);
riscv_core.mnemonic = mnemonic;
imm = id_stage_i.imm_uj_type;
$fdisplay(f, "%s\tx%0d, 0x%h (-> 0x%h)", mnemonic, rd, imm, imm+pc);
end
endfunction // printUJInstr
function void printRDInstr(input string mnemonic);
begin
riscv_core.mnemonic = mnemonic;
$fdisplay(f, "%s\tx%0d", mnemonic, rd);
end
endfunction // printRDInstr
`endif // TRACE_EXECUTION
// synopsis translate on
// synopsys translate_on
///////////////////