Major RiscV update, now supports compressed instructions (partially, work-in-progress until full standard is released)

This commit is contained in:
Sven Stucki 2015-06-12 19:21:46 +02:00
parent aa1821ba2d
commit f11858a8d8
6 changed files with 389 additions and 133 deletions

211
compressed_decoder.sv Normal file
View file

@ -0,0 +1,211 @@
////////////////////////////////////////////////////////////////////////////////
// Company: IIS @ ETHZ - Federal Institute of Technology //
// //
// Engineer: Sven Stucki - svstucki@student.ethz.ch //
// //
// Additional contributions by: //
// //
// //
// Create Date: 10/06/2015 //
// Design Name: Compressed Instruction Decoder //
// Module Name: id_stage.sv //
// Project Name: RiscV //
// Language: SystemVerilog //
// //
// Description: Decodes RISC-V compressed instructions into their RV32 //
// equivalent. This module is fully combinatorial. //
// //
// Revision: //
// Revision v0.1 - File Created //
// //
// //
////////////////////////////////////////////////////////////////////////////////
`include "defines.sv"
module compressed_decoder
(
input logic [31:0] instr_i,
output logic [31:0] instr_o,
output logic is_compressed_o,
output logic illegal_instr_o
);
//////////////////////////////////////////////////////////////////////////////////////////////////////
// ____ _ ____ _ //
// / ___|___ _ __ ___ _ __ _ __ ___ ___ ___ ___ __| | | _ \ ___ ___ ___ __| | ___ _ __ //
// | | / _ \| '_ ` _ \| '_ \| '__/ _ \/ __/ __|/ _ \/ _` | | | | |/ _ \/ __/ _ \ / _` |/ _ \ '__| //
// | |__| (_) | | | | | | |_) | | | __/\__ \__ \ __/ (_| | | |_| | __/ (_| (_) | (_| | __/ | //
// \____\___/|_| |_| |_| .__/|_| \___||___/___/\___|\__,_| |____/ \___|\___\___/ \__,_|\___|_| //
// |_| //
//////////////////////////////////////////////////////////////////////////////////////////////////////
always_comb
begin
illegal_instr_o = 1'b0;
is_compressed_o = 1'b1;
instr_o = '0;
unique case (instr_i[1:0])
// C0
2'b00: begin
unique case (instr_i[15:13])
3'b000: begin
if (instr_i[12] == 1'b0) begin
// c.mv -> add rd, x0, rs2
instr_o = {7'b0, instr_i[6:2], 5'b0, 3'b0, instr_i[11:7], `OPCODE_OP};
end else begin
// c.add -> add rd, rd, rs2
instr_o = {7'b0, instr_i[6:2], instr_i[11:7], 3'b000, instr_i[11:7], `OPCODE_OP};
end
if (instr_i[11:7] == 5'b0) illegal_instr_o = 1'b1;
end
3'b010: begin
// c.sw -> sw rs2', imm(rs1')
instr_o = {5'b0, instr_i[5], instr_i[12], 2'b01, instr_i[4:2], 2'b01, instr_i[9:7], 3'b010, instr_i[11:10], instr_i[6], 2'b00, `OPCODE_STORE};
end
3'b011: begin
unique case ({instr_i[12:10], instr_i[6:5]})
5'b00001: begin
// c.xor -> xor rd', rd', rs2'
instr_o = {7'b0, 2'b01, instr_i[4:2], 2'b01, instr_i[9:7], 3'b100, 2'b01, instr_i[9:7], `OPCODE_OP};
end
default: illegal_instr_o = 1'b1;
endcase
end
3'b101: begin
unique case (instr_i[6:5])
// c.and3 -> and rd', rs1', rs2'
2'b11: instr_o = {7'b0, 2'b01, instr_i[4:2], 2'b01, instr_i[9:7], 3'b111, 2'b01, instr_i[12:10], `OPCODE_OP};
default: illegal_instr_o = 1'b1;
endcase
end
3'b110: begin
// c.lw -> lw rd', imm(rs1')
instr_o = {5'b0, instr_i[5], instr_i[12:10], instr_i[6], 2'b00, 2'b01, instr_i[9:7], 3'b010, 2'b01, instr_i[4:2], `OPCODE_LOAD};
end
default: begin
illegal_instr_o = 1'b1;
end
endcase
end
// C1
2'b01: begin
unique case (instr_i[15:13])
3'b000: begin
// c.slli -> slli rd, rd, shamt
instr_o = {7'b0, instr_i[12], instr_i[6:2], instr_i[11:7], 3'b001, instr_i[11:7], `OPCODE_OPIMM};
if (instr_i[11:7] == 5'b0) illegal_instr_o = 1'b1;
if ({instr_i[12], instr_i[6:2]} == 6'b0) illegal_instr_o = 1'b1;
end
3'b010: begin
// c.swsp -> sw rs2, imm(x2)
instr_o = {4'b0, instr_i[8:7], instr_i[12], instr_i[6:2], 5'h02, 3'b000, instr_i[11:9], 2'b00, `OPCODE_STORE};
end
3'b100: begin
unique case (instr_i[6:5])
// c.orin -> ori rd', rs1', imm
2'b10: instr_o = {{8 {instr_i[12]}}, instr_i[12:10], 2'b01, instr_i[9:7], 3'b110, 2'b01, instr_i[4:2], `OPCODE_OPIMM};
default: illegal_instr_o = 1'b1;
endcase
if (instr_i[12:10] == 3'b0) illegal_instr_o = 1'b1;
end
3'b101: begin
// c.addi4spn -> addi rd', x2, imm
instr_o = {2'b0, instr_i[10:7], instr_i[12:11], instr_i[5], instr_i[6], 2'b00, 5'h02, 3'b000, 2'b01, instr_i[4:2], `OPCODE_OPIMM};
end
3'b110: begin
// c.lwsp -> lw rd, imm(x2)
instr_o = {4'b0, instr_i[3:2], instr_i[12], instr_i[6:4], 2'b00, 5'h02, 3'b010, instr_i[11:7], `OPCODE_LOAD};
if (instr_i[11:7] == 5'b0) illegal_instr_o = 1'b1;
end
default: begin
illegal_instr_o = 1'b1;
end
endcase
end
// C2
2'b10: begin
unique case (instr_i[15:13])
3'b000, 3'b001: begin
// 0: c.j -> jal x0, imm
// 1: c.jal -> jal x1, imm
instr_o = {instr_i[12], instr_i[11:7], instr_i[2], instr_i[6:3], {9 {instr_i[12]}}, 4'b0, instr_i[13], `OPCODE_JAL};
end
3'b011: begin
// c.bnez -> bne rs1', x0, imm
instr_o = {{3 {instr_i[12]}}, instr_i[12:10], instr_i[2], 5'b0, 2'b01, instr_i[9:7], 3'b001, instr_i[6:3], instr_i[12], `OPCODE_BRANCH};
end
3'b100: begin
if ({instr_i[12], instr_i[6:2]} == 6'b0) begin
// c.jr -> jalr x0, rs1, 0
instr_o = {12'b0, instr_i[11:7], 3'b0, 5'b0, `OPCODE_JALR};
end else begin
// c.li -> addi rd, x0, nzimm
instr_o = {6'b0, instr_i[12], instr_i[6:2], 5'b0, 3'b0, instr_i[11:7], `OPCODE_OPIMM}; // TODO: sign-extend
end
if (instr_i[11:7] == 5'b0) illegal_instr_o = 1'b1;
end
3'b101: begin
// c.jalr -> jalr x1, rs1, 0
instr_o = {12'b0, instr_i[11:7], 3'b000, 5'b00001, `OPCODE_JALR};
if (instr_i[11:7] == 5'b0) illegal_instr_o = 1'b1;
end
// c.lui
3'b110: begin
if (instr_i[11:7] == 5'b0) begin
// c.addi16sp -> addi x2, x2, nzimm
instr_o = {{3 {instr_i[12]}}, instr_i[4:2], instr_i[5], instr_i[6], 4'b0, 5'h02, 3'b000, 5'h02, `OPCODE_OPIMM};
end else begin
// c.addi -> addi rd, rd, nzimm
instr_o = {{6 {instr_i[12]}}, instr_i[12], instr_i[6:2], instr_i[11:7], 3'b0, instr_i[11:7], `OPCODE_OPIMM};
end
if ({instr_i[12], instr_i[6:2]} == 6'b0) illegal_instr_o = 1'b1;
end
3'b111: begin
// c.andi -> andi rd, rd, nzimm
instr_o = {6'b0, instr_i[12], instr_i[6:2], instr_i[11:7], 3'b111, instr_i[11:7], `OPCODE_OPIMM};
if (instr_i[11:7] == 5'b0) illegal_instr_o = 1'b1;
end
default: begin
illegal_instr_o = 1'b1;
end
endcase
end
2'b11: begin
// 32 bit (or more) instruction
instr_o = instr_i;
is_compressed_o = 1'b0;
end
default: begin
instr_o = 32'b0;
is_compressed_o = 1'b0;
illegal_instr_o = 1'b1;
end
endcase
end
endmodule

View file

@ -33,117 +33,117 @@
module controller
(
input logic clk,
input logic rst_n,
input logic clk,
input logic rst_n,
input logic fetch_enable_i, // Start the decoding
output logic core_busy_o, // Core is busy processing instructions
input logic fetch_enable_i, // Start the decoding
output logic core_busy_o, // Core is busy processing instructions
output logic force_nop_o,
output logic force_nop_o,
input logic [31:0] instr_rdata_i, // Instruction read from instr memory/cache: (sampled in the if stage)
output logic instr_req_o, // Fetch instruction Request:
input logic instr_gnt_i, // grant from icache
input logic instr_ack_i, // Acknow from instr memory or cache (means that data is available)
input logic [31:0] instr_rdata_i, // Instruction read from instr memory/cache: (sampled in the if stage)
output logic instr_req_o, // Fetch instruction Request:
input logic instr_gnt_i, // grant from icache
input logic instr_ack_i, // Acknow from instr memory or cache (means that data is available)
output logic [2:0] pc_mux_sel_o, // Selector in the Fetch stage to select the rigth PC (normal, jump ...)
output logic pc_mux_boot_o, // load boot address as PC, goes to the IF stage
output logic [2:0] pc_mux_sel_o, // Selector in the Fetch stage to select the rigth PC (normal, jump ...)
output logic pc_mux_boot_o, // load boot address as PC, goes to the IF stage
// ALU signals
output logic [`ALU_OP_WIDTH-1:0] alu_operator_o, // Operator in the Ex stage for the ALU block
output logic extend_immediate_o, // Extend a 16 bit immediate to 32 bit
output logic [1:0] alu_op_a_mux_sel_o, // Operator a is selected between reg value, PC or immediate
output logic [1:0] alu_op_b_mux_sel_o, // Operator b is selected between reg value or immediate
output logic alu_op_c_mux_sel_o, // Operator c is selected between reg value or PC
output logic alu_pc_mux_sel_o, // selects IF or ID PC for ALU computations
output logic [3:0] immediate_mux_sel_o,
output logic [`ALU_OP_WIDTH-1:0] alu_operator_o, // Operator in the Ex stage for the ALU block
output logic extend_immediate_o, // Extend a 16 bit immediate to 32 bit
output logic [1:0] alu_op_a_mux_sel_o, // Operator a is selected between reg value, PC or immediate
output logic [1:0] alu_op_b_mux_sel_o, // Operator b is selected between reg value or immediate
output logic alu_op_c_mux_sel_o, // Operator c is selected between reg value or PC
output logic alu_pc_mux_sel_o, // selects IF or ID PC for ALU computations
output logic [3:0] immediate_mux_sel_o,
output logic [1:0] vector_mode_o, // selects between 32 bit, 16 bit and 8 bit vectorial modes
output logic scalar_replication_o, // activates scalar_replication for vectorial mode
output logic [1:0] alu_cmp_mode_o, // selects comparison mode for ALU (i.e. full, any, all)
output logic [1:0] vector_mode_o, // selects between 32 bit, 16 bit and 8 bit vectorial modes
output logic scalar_replication_o, // activates scalar_replication for vectorial mode
output logic [1:0] alu_cmp_mode_o, // selects comparison mode for ALU (i.e. full, any, all)
// Mupliplicator related control signals
output logic mult_en_o, // Multiplication operation is running
output logic [1:0] mult_sel_subword_o, // Select subwords for 16x16 bit of multiplier
output logic [1:0] mult_signed_mode_o, // Multiplication in signed mode
output logic mult_use_carry_o, // Use carry for MAC
output logic mult_mac_en_o, // Use the accumulator after multiplication
output logic mult_en_o, // Multiplication operation is running
output logic [1:0] mult_sel_subword_o, // Select subwords for 16x16 bit of multiplier
output logic [1:0] mult_signed_mode_o, // Multiplication in signed mode
output logic mult_use_carry_o, // Use carry for MAC
output logic mult_mac_en_o, // Use the accumulator after multiplication
output logic regfile_wdata_mux_sel_o, // Mul selctor used in WB stage to select regfile wdata from ex result (ALU-MUL), from data memory, or special registers
input logic regfile_wdata_mux_sel_ex_i, // FW signal: Mul selctor used in WB stage to select regfile wdata from ex result (ALU-MUL), from data memory, or special registers
output logic regfile_we_o, // Write Enable to regfile
output logic [1:0] regfile_alu_waddr_mux_sel_o, // Select register write address for ALU/MUL operations
output logic regfile_wdata_mux_sel_o, // Mul selctor used in WB stage to select regfile wdata from ex result (ALU-MUL), from data memory, or special registers
input logic regfile_wdata_mux_sel_ex_i, // FW signal: Mul selctor used in WB stage to select regfile wdata from ex result (ALU-MUL), from data memory, or special registers
output logic regfile_we_o, // Write Enable to regfile
output logic [1:0] regfile_alu_waddr_mux_sel_o, // Select register write address for ALU/MUL operations
output logic regfile_alu_we_o, // Write Enable to regfile 2nd port
output logic regfile_alu_we_o, // Write Enable to regfile 2nd port
output logic prepost_useincr_o, // When not active bypass the alu result=op_a
input logic data_misaligned_i,
output logic prepost_useincr_o, // When not active bypass the alu result=op_a
input logic data_misaligned_i,
// CSR manipulation
output logic csr_access_o,
output logic [1:0] csr_op_o,
output logic csr_access_o,
output logic [1:0] csr_op_o,
// LD/ST unit signals
output logic data_we_o, // Write enable to data memory
output logic [1:0] data_type_o, // Data type on data memory: byte, half word or word
output logic data_sign_extension_o, // Sign extension on read data from data memory
output logic [1:0] data_reg_offset_o, // Offset in bytes inside register for stores
output logic data_req_o, // Request for a transaction to data memory
input logic data_ack_i, // Data memory request-acknowledge
input logic data_req_ex_i, // Delayed copy of the data_req_o
input logic data_rvalid_i, // rvalid from data memory
output logic data_we_o, // Write enable to data memory
output logic [1:0] data_type_o, // Data type on data memory: byte, half word or word
output logic data_sign_extension_o, // Sign extension on read data from data memory
output logic [1:0] data_reg_offset_o, // Offset in bytes inside register for stores
output logic data_req_o, // Request for a transaction to data memory
input logic data_ack_i, // Data memory request-acknowledge
input logic data_req_ex_i, // Delayed copy of the data_req_o
input logic data_rvalid_i, // rvalid from data memory
// hwloop signals
output logic [2:0] hwloop_we_o, // write enables for hwloop regs
output logic hwloop_wb_mux_sel_o, // select data to write to hwloop regs
output logic [1:0] hwloop_cnt_mux_sel_o, // selects hwloop counter input
input logic hwloop_jump_i, // modify pc_mux_sel to select the hwloop addr
output logic [2:0] hwloop_we_o, // write enables for hwloop regs
output logic hwloop_wb_mux_sel_o, // select data to write to hwloop regs
output logic [1:0] hwloop_cnt_mux_sel_o, // selects hwloop counter input
input logic hwloop_jump_i, // modify pc_mux_sel to select the hwloop addr
// Interrupt signals
input logic irq_present_i, // there is an IRQ, so if we are sleeping we should wake up now
input logic irq_present_i, // there is an IRQ, so if we are sleeping we should wake up now
// Exception Controller Signals
output logic illegal_insn_o, // illegal instruction encountered
output logic trap_insn_o, // trap instruction encountered
output logic pipe_flush_o, // pipe flush requested by controller
input logic pc_valid_i, // is the next_pc currently valid?
output logic clear_isr_running_o, // an l.rfe instruction was encountered, exit ISR
input logic pipe_flushed_i, // Pipe is flushed
input logic trap_hit_i, // a trap was hit, so we have to flush EX and WB
output logic illegal_insn_o, // illegal instruction encountered
output logic trap_insn_o, // trap instruction encountered
output logic pipe_flush_o, // pipe flush requested by controller
input logic pc_valid_i, // is the next_pc currently valid?
output logic clear_isr_running_o, // an l.rfe instruction was encountered, exit ISR
input logic pipe_flushed_i, // Pipe is flushed
input logic trap_hit_i, // a trap was hit, so we have to flush EX and WB
// Debug Unit Signals
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, // trap hit, inform debug unit
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, // trap hit, inform debug unit
// SPR Signals
input logic sr_flag_fw_i, // forwared branch signal
input logic sr_flag_i, // branch signal
input logic set_flag_ex_i, // alu is currently updating the flag if 1
output logic set_flag_o, // to special purpose registers --> flag
output logic set_carry_o, // to special purpose registers --> carry
output logic set_overflow_o, // to special purpose registers --> overflow
output logic restore_sr_o, // restores status register after interrupt
input logic sr_flag_fw_i, // forwared branch signal
input logic sr_flag_i, // branch signal
input logic set_flag_ex_i, // alu is currently updating the flag if 1
output logic set_flag_o, // to special purpose registers --> flag
output logic set_carry_o, // to special purpose registers --> carry
output logic set_overflow_o, // to special purpose registers --> overflow
output logic restore_sr_o, // restores status register after interrupt
// Forwarding signals from regfile
input logic [4:0] regfile_waddr_ex_i, // FW: write address from EX stage
input logic regfile_we_ex_i, // FW: write enable from EX stage
input logic [4:0] regfile_waddr_wb_i, // FW: write address from WB stage
input logic regfile_we_wb_i, // FW: write enable from WB stage
input logic [4:0] regfile_alu_waddr_fw_i, // FW: ALU/MUL write address from EX stage
input logic regfile_alu_we_fw_i, // FW: ALU/MUL write enable from EX stage
output logic [1:0] operand_a_fw_mux_sel_o, // regfile ra data selector form ID stage
output logic [1:0] operand_b_fw_mux_sel_o, // regfile rb data selector form ID stage
output logic [1:0] operand_c_fw_mux_sel_o, // regfile rc data selector form ID stage
input logic [4:0] regfile_waddr_ex_i, // FW: write address from EX stage
input logic regfile_we_ex_i, // FW: write enable from EX stage
input logic [4:0] regfile_waddr_wb_i, // FW: write address from WB stage
input logic regfile_we_wb_i, // FW: write enable from WB stage
input logic [4:0] regfile_alu_waddr_fw_i, // FW: ALU/MUL write address from EX stage
input logic regfile_alu_we_fw_i, // FW: ALU/MUL write enable from EX stage
output logic [1:0] operand_a_fw_mux_sel_o, // regfile ra data selector form ID stage
output logic [1:0] operand_b_fw_mux_sel_o, // regfile rb data selector form ID stage
output logic [1:0] operand_c_fw_mux_sel_o, // regfile rc data selector form ID stage
// Jump target calcuation done detection
input logic [1:0] jump_in_ex_i, // jump is being calculated in ALU
output logic [1:0] jump_in_id_o, // jump is being calculated in ALU
// Jump target calcuation done decision
input logic [1:0] jump_in_ex_i, // jump is being calculated in ALU
output logic [1:0] jump_in_id_o, // jump is being calculated in ALU
output logic stall_if_o, // Stall IF stage (deassert requests)
output logic stall_id_o, // Stall ID stage (and instr and data memory interface) ( ID_STAGE )
output logic stall_ex_o, // Stall ex stage ( EX_STAGE )
output logic stall_wb_o // Stall write to register file due contentions ( WB_STAGE )
output logic stall_if_o, // Stall IF stage (deassert requests)
output logic stall_id_o, // Stall ID stage (and instr and data memory interface) ( ID_STAGE )
output logic stall_ex_o, // Stall ex stage ( EX_STAGE )
output logic stall_wb_o // Stall write to register file due contentions ( WB_STAGE )
);
// FSM state encoding
@ -170,20 +170,23 @@ module controller
logic set_carry;
logic deassert_we;
logic lsu_stall;
logic misalign_stall;
logic instr_ack_stall;
logic load_stall;
logic jr_stall;
logic trap_stall;
logic lsu_stall;
logic misalign_stall;
logic instr_ack_stall;
logic load_stall;
logic jr_stall;
logic trap_stall;
logic set_npc;
logic set_npc;
`ifdef BRANCH_PREDICTION
logic wrong_branch_taken;
logic wrong_branch_taken;
`endif
logic rega_used;
logic regb_used;
logic regc_used;
logic rega_used;
logic regb_used;
logic regc_used;
logic [31:0] instr;
logic compressed_instr;
// dbg fsm
enum logic [2:0] { DBG_IDLE, DBG_EX, DBG_WB, DBG_STALL, DBG_FLUSH, DBG_FLUSH2 } dbg_fsm_cs, dbg_fsm_ns;
@ -346,7 +349,7 @@ module controller
alu_pc_mux_sel_o = 1'b1;
alu_op_a_mux_sel_o = `OP_A_CURRPC;
alu_op_b_mux_sel_o = `OP_B_IMM;
immediate_mux_sel_o = `IMM_HEX4;
immediate_mux_sel_o = `IMM_PCINCR;
alu_operator = `ALU_ADD;
regfile_alu_we = 1'b1;
// Calculate jump target (= PC + UJ imm)
@ -365,7 +368,7 @@ module controller
alu_pc_mux_sel_o = 1'b1;
alu_op_a_mux_sel_o = `OP_A_CURRPC;
alu_op_b_mux_sel_o = `OP_B_IMM;
immediate_mux_sel_o = `IMM_HEX4;
immediate_mux_sel_o = `IMM_PCINCR;
alu_operator = `ALU_ADD;
regfile_alu_we = 1'b1;
// Calculate jump target (= RS1 + I imm)

View file

@ -53,7 +53,7 @@ module id_stage
output logic [1:0] jump_in_ex_o,
// IF and ID stage signals
output logic compressed_instr_o,
output logic [2:0] pc_mux_sel_o,
output logic pc_mux_boot_o,
output logic [1:0] exc_pc_mux_o,
@ -168,6 +168,10 @@ module id_stage
);
// Compressed instruction decoding
logic [31:0] instr;
logic illegal_compressed_instr;
// Immediate decoding and sign extension
logic [31:0] imm_i_type;
logic [31:0] imm_s_type;
@ -288,27 +292,38 @@ module id_stage
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;
// compressed instruction decoding
compressed_decoder compressed_decoder_i (
.instr_i (instr_rdata_i),
.instr_o (instr),
.is_compressed_o (compressed_instr_o),
.illegal_instr_o (illegal_compressed_instr)
);
// immediate extraction and sign extension
assign imm_i_type = { {20 {instr_rdata_i[31]}}, instr_rdata_i[31:20] };
assign imm_s_type = { {20 {instr_rdata_i[31]}}, instr_rdata_i[31:25], instr_rdata_i[11:7] };
assign imm_sb_type = { {20 {instr_rdata_i[31]}}, instr_rdata_i[31], instr_rdata_i[7],
instr_rdata_i[30:25], instr_rdata_i[11:8], 1'b0 };
assign imm_u_type = { instr_rdata_i[31:12], {12 {1'b0}} };
assign imm_uj_type = { {20 {instr_rdata_i[31]}}, instr_rdata_i[19:12],
instr_rdata_i[20], instr_rdata_i[30:21], 1'b0 };
assign imm_i_type = { {20 {instr[31]}}, instr[31:20] };
assign imm_s_type = { {20 {instr[31]}}, instr[31:25], instr[11:7] };
assign imm_sb_type = { {20 {instr[31]}}, instr[31], instr[7],
instr[30:25], instr[11:8], 1'b0 };
assign imm_u_type = { instr[31:12], {12 {1'b0}} };
assign imm_uj_type = { {20 {instr[31]}}, instr[19:12],
instr[20], instr[30:21], 1'b0 };
// immediate for CSR manipulatin (zero extended)
assign imm_z_type = { 27'b0, instr_rdata_i[`REG_S1] };
assign imm_z_type = { 27'b0, instr[`REG_S1] };
// source registers
assign regfile_addr_ra_id = instr_rdata_i[`REG_S1];
assign regfile_addr_rb_id = instr_rdata_i[`REG_S2];
//assign regfile_addr_rc_id = instr_rdata_i[25:21];
assign regfile_addr_ra_id = instr[`REG_S1];
assign regfile_addr_rb_id = instr[`REG_S2];
//assign regfile_addr_rc_id = instr[25:21];
// destination registers
assign regfile_waddr_id = instr_rdata_i[`REG_D];
assign regfile_waddr_id = instr[`REG_D];
//assign alu_vec_ext = instr_rdata_i[9:8]; TODO
//assign alu_vec_ext = instr[9:8]; TODO
assign alu_vec_ext = 1'b0;
@ -355,7 +370,7 @@ module id_stage
end
// hwloop register id
assign hwloop_regid = instr_rdata_i[22:21]; // set hwloop register id
assign hwloop_regid = instr[22:21]; // set hwloop register id
//////////////////////////////////////////////////////////////////
// _ _____ _ //
@ -368,12 +383,12 @@ module id_stage
always_comb
begin
unique case (instr_rdata_i[6:0])
unique case (instr[6:0])
`OPCODE_JAL: jump_target = current_pc_id_i + imm_uj_type;
`OPCODE_JALR: jump_target = operand_a_fw_id + imm_i_type;
`OPCODE_BRANCH: jump_target = current_pc_id_i + imm_sb_type;
default: jump_target = '0;
endcase // unique case (instr_rdata_i[6:0])
endcase // unique case (instr[6:0])
end
@ -421,13 +436,12 @@ module id_stage
// Immediate Mux for operand B
always_comb
begin : immediate_mux
case (immediate_mux_sel)
//`IMM_VEC: immediate_b = immediate_vec_id;
`IMM_I: immediate_b = imm_i_type;
`IMM_S: immediate_b = imm_s_type;
`IMM_U: immediate_b = imm_u_type;
`IMM_HEX4: immediate_b = 32'h4;
default: immediate_b = 32'h4;
unique case (immediate_mux_sel)
//`IMM_VEC: immediate_b = immediate_vec_id;
`IMM_I: immediate_b = imm_i_type;
`IMM_S: immediate_b = imm_s_type;
`IMM_U: immediate_b = imm_u_type;
`IMM_PCINCR: immediate_b = compressed_instr_o ? 32'h2 : 32'h4;
endcase; // case (immediate_mux_sel)
end
@ -547,7 +561,7 @@ module id_stage
.force_nop_o ( force_nop_controller ),
// Signal from-to PC pipe (instr rdata) and instr mem system (req and ack)
.instr_rdata_i ( instr_rdata_i ),
.instr_rdata_i ( instr ),
.instr_req_o ( instr_req_o ),
.instr_gnt_i ( instr_gnt_i ),
.instr_ack_i ( instr_ack_i ),

View file

@ -49,6 +49,7 @@ module if_stage
output logic [31:0] instr_addr_o, // address for instruction fetch
// Forwarding ports - control signals
input logic compressed_instr_i, // ID decoded a compressed instruction
input logic force_nop_i, // insert a NOP in the pipe
input logic [31:0] exception_pc_reg_i, // address used to restore the program counter when the interrupt/exception is served
input logic [31:0] pc_from_hwloop_i, // pc from hwloop start addr
@ -75,7 +76,8 @@ module if_stage
////////////////////////////////////
// Instruction Fetch (IF) signals //
////////////////////////////////////
logic [31:0] next_pc; // Next program counter
logic [31:0] next_pc; // Next PC (directly sent to I$)
logic [31:0] incr_pc; // Increased PC
logic [31:0] exc_pc; // Exception PC
logic [31:0] instr_rdata_int; // The instruction read from instr memory/cache is forwarded to ID stage, and the controller can force this forwarding to a nop (BUBBLE)
@ -94,6 +96,17 @@ module if_stage
endcase //~case (exc_pc_mux_i)
end
// increased PC calculation
always_comb
begin
if (instr_rdata_i[1:0] != 2'b11) begin
// compressed instruction
incr_pc = current_pc_if_o + 32'd2;
end else begin
incr_pc = current_pc_if_o + 32'd4;
end
end
// PC selection and force NOP logic
always_comb
begin
@ -101,10 +114,10 @@ module if_stage
instr_rdata_int = instr_rdata_i;
unique case (pc_mux_sel_i)
`PC_INCR: next_pc = current_pc_if_o + 32'd4; // PC is incremented and points the next instruction
`PC_INCR: next_pc = incr_pc; // 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
`PC_ERET: next_pc = exception_pc_reg_i; // restore the PC when returning from IRQ/exception
`PC_ERET: next_pc = exception_pc_reg_i; // PC is restored when returning from IRQ/exception
`HWLOOP_ADDR: next_pc = pc_from_hwloop_i; // PC is taken from hwloop start addr
default:
begin

View file

@ -328,10 +328,10 @@ endfunction // prettyPrintInstruction
`define OP_C_JT 1'b1
// operand b immediate selection
`define IMM_I 2'b00
`define IMM_S 2'b01
`define IMM_U 2'b10
`define IMM_HEX4 2'b11
`define IMM_I 2'b00
`define IMM_S 2'b01
`define IMM_U 2'b10
`define IMM_PCINCR 2'b11
// PC mux selector defines
`define PC_INCR 3'b000

View file

@ -84,6 +84,8 @@ module riscv_core
logic pc_mux_boot; // load boot address as PC
logic [1:0] exc_pc_mux_id; // Mux selector for exception PC
logic compressed_instr;
logic useincr_addr_ex; // Active when post increment
logic data_misaligned; // Active when post increment
@ -302,6 +304,8 @@ module riscv_core
.branch_decision_i ( branch_decision ),
.jump_target_i ( jump_target ),
.compressed_instr_i ( compressed_instr ),
// pipeline stalls
.stall_if_i ( stall_if ),
.stall_id_i ( stall_id )
@ -373,6 +377,8 @@ module riscv_core
.current_pc_if_i ( current_pc_if ),
.current_pc_id_i ( current_pc_id ),
.compressed_instr_o ( compressed_instr ),
.sr_flag_fw_i ( sr_flag_fw ),
.sr_flag_i ( sr_flag ),
@ -835,6 +841,7 @@ module riscv_core
integer f;
string fn;
logic [31:0] instr;
logic compressed;
logic [31:0] pc;
logic [5:0] rd, rs1, rs2;
logic [31:0] rs1_value, rs2_value;
@ -861,15 +868,16 @@ module riscv_core
#1
// get current PC and instruction
instr = id_stage_i.instr_rdata_i[31:0];
pc = id_stage_i.current_pc_id_i;
instr = id_stage_i.instr[31:0];
compressed = id_stage_i.compressed_instr_o;
pc = id_stage_i.current_pc_id_i;
// get register values
rd = instr[`REG_D];
rs1 = instr[`REG_S1];
rs1_value = id_stage_i.operand_a_fw_id; //r[rs1];
rs2 = instr[`REG_S2];
rs2_value = id_stage_i.operand_b_fw_id; //r[rs2];
rd = instr[`REG_D];
rs1 = instr[`REG_S1];
rs1_value = id_stage_i.operand_a_fw_id; //r[rs1];
rs2 = instr[`REG_S2];
rs2_value = id_stage_i.operand_b_fw_id; //r[rs2];
if (id_stage_i.stall_id_o == 1'b0 && id_stage_i.controller_i.ctrl_fsm_cs == id_stage_i.controller_i.DECODE)
begin
@ -877,6 +885,13 @@ module riscv_core
imm = 0;
$fwrite(f, "%t:\t0x%h\t0x%h\t", $time, pc, instr);
if (compressed)
//$fwrite(f, "C (0x%4h)\t", id_stage_i.instr_rdata_i[15:0]);
$fwrite(f, "C\t");
else
$fwrite(f, "I\t");
// use casex instead of case inside due to ModelSim bug
casex (instr)
// Aliases
32'h00_00_00_13: printMnemonic("NOP");