imm_gen and formatted

master
郑几方 3 years ago
commit d00492399c

@ -1,38 +1,94 @@
import binandint
from binandint import *
def alu(a, b, alu_ctrl): # a,b为两个运算数alu_ctrl为控制信号返回运算结果result与是否为0 zero
if alu_ctrl == '00000':
pass
elif alu_ctrl == '00001':
pass
elif alu_ctrl == '00010':
pass
elif alu_ctrl == '00011':
pass
elif alu_ctrl == '00100':
pass
elif alu_ctrl == '00101':
pass
elif alu_ctrl == '00110':
pass
elif alu_ctrl == '00111':
pass
elif alu_ctrl == '01000':
pass
signed = a - b
if alu_ctrl == '00000': # add,jalr
alu_result = a + b
elif alu_ctrl == '00001': # sub
alu_result = a - b
elif alu_ctrl == '00010': # or
alu_result = a | b
elif alu_ctrl == '00011': # and
alu_result = a & b
elif alu_ctrl == '00100': # slt
if (signed >= 0):
alu_result = 0
else:
alu_result = 1
elif alu_ctrl == '00101': # beq
if a == b:
alu_result = 1
else:
alu_result = 0
elif alu_ctrl == '00110': # bne
if a != b:
alu_result = 1
else:
alu_result = 0
elif alu_ctrl == '00111': # blt
if a < b:
alu_result = 1
else:
alu_result = 0
elif alu_ctrl == '01000': # bge
if a >= b:
alu_result = 1
else:
alu_result = 0
elif alu_ctrl == '01001':
pass
if a < 0:
ua = a + 2**32
else:
ua = a
if b < 0:
ub = b + 2**32
else:
ub = b
if ua < ub:
alu_result = 1
else:
alu_result = 0
elif alu_ctrl == '01010':
pass
if a < 0:
ua = a + 2**32
else:
ua = a
if b < 0:
ub = b + 2**32
else:
ub = b
if ua >= ub:
alu_result = 1
else:
alu_result = 0
elif alu_ctrl == '01011':
pass
alu_result = 1
elif alu_ctrl == '01100':
pass
alu_result = a ^ b
elif alu_ctrl == '01101':
pass
alu_result = a << b
elif alu_ctrl == '01110':
pass
if a < 0:
ua = a + 2**32
else:
ua = a
if b < 0:
ub = b + 2**32
else:
ub = b
if ua <= ub:
alu_result = 1
else:
alu_result = 0
elif alu_ctrl == '01111':
pass
if a < 0:
ua = a + 2**32
else:
ua = a
alu_result = a >> b
elif alu_ctrl == '10000':
alu_result = a >> b
else:
pass
alu_result = 0
return alu_result

@ -17,3 +17,10 @@ def InttoBin(x, n):
if x < 0:
x += 2**n
return UInttoBin(x, n)
def unsigned_ext(x, n):
return '0' * (n - len(x)) + x
def signed_ext(x, n):
return x[0] * (n - len(x)) + x

@ -1,28 +1,49 @@
from binandint import *
class data_mem:
memory = [8 * '0'] * 4 * 1024 * 16
def __init__(self) -> None:
pass
def mem(self, write_en, read_en, address, data_in, funct3
): # 写使能,读使能,(使能为int的0或1)地址输入数据func3 # 输出为data_out
): # 写使能,读使能,(使能为int的0或1)地址输入数据func3 #输出为data_out
if write_en:
if funct3 == '000':
pass
elif funct3 == '001':
pass
elif funct3 == '010':
pass
if funct3 == '000': # sb
self.memory[address] = InttoBin(data_in % 2**8, 8)
elif funct3 == '001': # sh
temp = InttoBin(data_in % 2**16, 16)
self.memory[address + 1] = temp[0:8]
self.memory[address] = temp[8:16]
elif funct3 == '010': # sw
temp = InttoBin(data_in, 32)
self.memory[address + 3] = temp[0:8]
self.memory[address + 2] = temp[8:16]
self.memory[address + 1] = temp[16:24]
self.memory[address] = temp[24:32]
else:
pass
if read_en:
if funct3 == '000':
pass
elif funct3 == '001':
pass
elif funct3 == '010':
pass
elif funct3 == '100':
pass
elif funct3 == '101':
pass
if funct3 == '000': # lb
data_out = BintoInt(self.memory[address])
elif funct3 == '001': # lh
data_out = BintoInt(self.memory[address + 1] +
self.memory[address])
elif funct3 == '010': # lw
data_out = BintoInt(self.memory[address + 3] +
self.memory[address + 2] +
self.memory[address + 1] +
self.memory[address])
elif funct3 == '100': # lbu
data_out = BintoUInt(self.memory[address + 1] +
self.memory[address])
elif funct3 == '101': # lhu
data_out = BintoUInt(self.memory[address + 3] +
self.memory[address + 2] +
self.memory[address + 1] +
self.memory[address])
else:
pass
return data_out

@ -0,0 +1,79 @@
from adder import *
from alu_controller import *
from alu import *
from binandint import *
from branch_unit import *
from data_mem import *
from forwarding_unit import *
from hazard_detector import *
from Imm_gen import *
from insn_mem import *
from mux import *
from mux4 import *
from proc_controller import *
from reg_file import reg_file
IM = insn_mem()
PC = 0
def IF(BrPC, Brflush, stall, PC, IM):
PCplus4 = adder(PC, 4)
if Brflush == '1':
nPC = BrPC
else:
nPC = PC + 4
insn = IM.fetch(nPC)
return nPC, insn
REG = reg_file()
def ID(PC, insn, RegWrite, Brflush, stall, REG, WB_data):
funct7 = insn[0:7]
rs2 = BintoUInt(insn[7:12])
rs1 = BintoUInt(insn[12:17])
funct3 = insn[17:20]
rd = BintoUInt(insn[20:25])
opcode = insn[25:32]
ALUSrc, MemtoReg, RegWritex, MemRead, MemWrite, ALUOp, Branch, JalrSel, RWSel = proc_controller(
opcode)
ImmG = Imm_gen(insn)
REG.write(RegWrite, rd, WB_data)
RD1, RD2 = REG.read(rs1, rs2)
return ALUSrc, MemtoReg, RegWritex, MemRead, MemWrite, ALUOp, Branch, JalrSel, RWSel, PC, RD1, RD2, ImmG, rs1, rs2, rd, funct3, funct7
def EX(ALUSrc, MemtoReg, RegWrite, MemRead, MemWrite, ALUOp, Branch, JalrSel,
RWSel, PC, RD1, RD2, ImmG, rs1, rs2, rd, funct3, funct7, lastrs1,
lastrs2, forwardA, forwardB, WB_data, alu_out):
stall = hazard_detector(lastrs1, lastrs2, rd, MemRead)
tempA = mux4(RD1, alu_out, WB_data, 0, forwardA)
tempB = mux4(RD2, alu_out, WB_data, 0, forwardB)
tempB2 = mux(tempB, ImmG, ALUSrc)
alu_ctrl = alu_controller(ALUOp, funct7, funct3)
ALU_result = alu(tempA, tempB2, alu_ctrl)
pc_plus_imm, pc_plus_4, branch_target, pc_sel = branch_unit(
PC, ImmG, JalrSel, Branch, ALU_result)
return MemtoReg, RegWrite, MemWrite, RWSel, MemRead, pc_plus_imm, pc_plus_4, branch_target, pc_sel, ALU_result, rs1, rs2, rd, tempA, tempB, funct3, funct7
MEMORY = data_mem()
def MEM(MEMORY, MemtoReg, RegWrite, MemWrite, RWSel, MemRead, pc_plus_imm,
pc_plus_4, ALU_result, rs1, rs2, rd, tempA, tempB, funct3, funct7):
data_out = MEMORY(MemWrite, MemRead, ALU_result, tempB, funct3)
return MemtoReg, RegWrite, RWSel, pc_plus_imm, pc_plus_4, data_out, tempB, rd
def WB(MemtoReg, RegWrite, RWSel, pc_plus_imm, pc_plus_4, data_out, tempB,
ex_mem_rd, mem_wb_rd, ex_mem_rs1, ex_mem_rs2, ex_mem_regwrite,
mem_wb_regwrite):
mem_out = mux(data_out, tempB, MemtoReg)
WB_data = mux4(mem_out, pc_plus_4, pc_plus_imm, 0, RWSel)
forward_a, forward_b = fowardingunit(ex_mem_rs1, ex_mem_rs2, ex_mem_rd,
mem_wb_rd, ex_mem_regwrite,
mem_wb_regwrite)
return WB_data, RegWrite, forward_a, forward_b

@ -1,6 +1,6 @@
def hazard_detector(if_id_rs1, if_id_rs2, id_ex_rd, id_ex_memread):
if id_ex_memread and (id_ex_rd == if_id_rs1 or id_ex_rd == if_id_rs2):
stall = 1
stall = '1'
else:
stall = 0
stall = '0'
return stall

@ -1,5 +1,10 @@
class insn_mem:
memory=[8*'0']*4*1024*16
def fetch(self,address):
insn=self.memory[address]
return insn
memory = [8*'0']*4*1024*16
def __init__(self) -> None:
pass
def fetch(self, address):
insn = self.memory[address+3]+self.memory[address+2] + \
self.memory[address+1]+self.memory[address]
return insn

@ -19,7 +19,7 @@ def proc_controller(opcode):
ALUSrc, MemtoReg, RegWrite, MemRead, MemWrite, ALUOp, Branch, JalrSel, RWSel='1','0','1','0','0','11','1','0','01'
#################################
elif opcode=='0010111': #(auipc)20位立即数
ALUSrc, MemtoReg, RegWrite, MemRead, MemWrite, ALUOp, Branch, JalrSel, RWSel='1','0','1','0','0','00','1','0','11'
ALUSrc, MemtoReg, RegWrite, MemRead, MemWrite, ALUOp, Branch, JalrSel, RWSel='1','0','1','0','0','00','1','0','10'
else:
ALUSrc, MemtoReg, RegWrite, MemRead, MemWrite, ALUOp, Branch, JalrSel, RWSel='0','0','0','0','0','00','0','0','00'
return ALUSrc, MemtoReg, RegWrite, MemRead, MemWrite, ALUOp, Branch, JalrSel, RWSel

@ -0,0 +1,14 @@
class reg_file:
regs = [0]*32
def __init__(self) -> None:
pass
def write(self, write_en, write_addr, data_in):
if write_en == '1' and write_addr != 0:
self.regs[write_addr] = data_in
def read(self, read_addr1, read_addr2):
data_out1 = self.regs[read_addr1]
data_out2 = self.regs[read_addr2]
return data_out1, data_out2

@ -0,0 +1 @@
from datapath import *

@ -0,0 +1,13 @@
`timescale 1ns / 1ps
// 加法器
module adder #(
parameter WIDTH = 8
)(
input logic [WIDTH-1:0] a, b,
output logic [WIDTH-1:0] y
);
// add your adder logic here
assign y = a + b;
endmodule

@ -0,0 +1,41 @@
`timescale 1ns / 1ps
// 算数逻辑单元
module alu #(
parameter DATA_WIDTH = 32,
parameter OPCODE_LENGTH = 4
)(
input logic[DATA_WIDTH - 1 : 0] operand_a,
input logic[DATA_WIDTH - 1 : 0] operand_b,
input logic[OPCODE_LENGTH - 1 : 0] alu_ctrl, // Operation
output logic[DATA_WIDTH - 1 : 0] alu_result,
output logic zero
);
// add your code here.
logic [31:0] s;
logic signed [31:0] signed_s, signed_operand_a, signed_operand_b;
assign signed_operand_a = $signed(operand_a);
assign signed_operand_b = $signed(operand_b);
assign signed_s = $signed(signed_operand_a - signed_operand_b);
assign s = operand_a - operand_b;
assign zero = (s == 32'b0)? 1'b1 : 1'b0;
always_comb
case (alu_ctrl)
4'b0000: alu_result = operand_a + operand_b; // add, jalr
4'b0001: alu_result = operand_a - operand_b; // sub
4'b0010: alu_result = operand_a | operand_b; // or
4'b0011: alu_result = operand_a & operand_b; // and
4'b0100: alu_result = {31'b0, signed_s[31]}; // slt
4'b0101: alu_result = (operand_a == operand_b)? 32'b1 : 32'b0; // beq
4'b0110: alu_result = (operand_a != operand_b)? 32'b1 : 32'b0; // bne
4'b0111: alu_result = (signed_operand_a < signed_operand_b)? 32'b1 : 32'b0; // blt
4'b1000: alu_result = (signed_operand_a >= signed_operand_b)? 32'b1 : 32'b0; // bge
4'b1001: alu_result = (operand_a < operand_b)? 32'b1 : 32'b0; // bltu
4'b1010: alu_result = (operand_a >= operand_b)? 32'b1 : 32'b0; // bgeu
4'b1011: alu_result = 32'b1; // jal
4'b1100: alu_result = operand_a ^ operand_b; // xor
default: alu_result = 32'b0;
endcase
endmodule

@ -0,0 +1,41 @@
`timescale 1ns / 1ps
// 算数逻辑单元控制器
module ALU_Controller (
input logic [1:0] alu_op, // 2-bit opcode field from the Proc_controller
input logic [6:0] funct7, // insn[31:25]
input logic [2:0] funct3, // insn[14:12]
output logic [3:0] operation // operation selection for ALU
);
// add your code here.
always_comb
case (alu_op)
2'b00: operation = 4'b0000; // lw, sw
2'b01:
case (funct3)
3'b000: operation = 4'b0101; // beq
3'b001: operation = 4'b0110; // bne
3'b100: operation = 4'b0111; // blt
3'b101: operation = 4'b1000; // bge
3'b110: operation = 4'b1001; // bltu
3'b111: operation = 4'b1010; // bgeu
default: operation = 4'b0000;
endcase
2'b10:
case (funct3)
3'b000:
case (funct7)
7'b0100000: operation = 4'b0001; // sub (存在addi的立即数恰好满足此情况的bug)
default: operation = 4'b0000; // add, addi
endcase
3'b100: operation = 4'b1100; // xor
3'b110: operation = 4'b0010; // or, ori
3'b111: operation = 4'b0011; // and, andi
3'b010: operation = 4'b0100; // slt
default: operation = 4'b0000;
endcase
2'b11: operation = 4'b1011; // jal
default: operation = 4'b0000;
endcase
endmodule

@ -0,0 +1,30 @@
`timescale 1ns / 1ps
// 跳转单元
module BranchUnit #(
parameter PC_W = 9
)(
input logic [PC_W - 1:0] cur_pc,
input logic [31:0] imm,
input logic jalr_sel,
input logic branch_taken, // Branch
input logic [31:0] alu_result,
output logic [31:0] pc_plus_imm, // PC + imm
output logic [31:0] pc_plus_4, // PC + 4
output logic [31:0] branch_target, // BrPC
output logic pc_sel
);
logic [31:0] pc;
assign pc = {23'b0, cur_pc};
always_comb
begin
pc_plus_4 = pc + 32'd4;
pc_plus_imm = pc + imm;
pc_sel = jalr_sel | (branch_taken & alu_result[0]);
if (jalr_sel == 1'b1)
branch_target = alu_result & 32'hfffffffe; // jalr
else
branch_target = pc + (imm << 1); // jal and beq
end
endmodule

@ -0,0 +1,38 @@
`timescale 1ns / 1ps
// 数据存储器
module datamemory#(
parameter ADDR_WIDTH = 12,
parameter DATA_WIDTH = 32
)(
input logic clock,
input logic read_en,
input logic write_en,
input logic [ADDR_WIDTH -1 : 0] address, // read/write address
input logic [DATA_WIDTH -1 : 0] data_in, // write Data
input logic [2:0] funct3, // insn[14:12]
output logic [DATA_WIDTH -1 : 0] data_out // read data
);
logic [DATA_WIDTH - 1 : 0] MEM[(2**(ADDR_WIDTH - 2)) - 1 : 0];
always @(posedge clock)
if (write_en) // sw etc.
case (funct3)
3'b000: MEM[address[ADDR_WIDTH - 1 : 2]][7:0] <= data_in; // sb
3'b001: MEM[address[ADDR_WIDTH - 1 : 2]][15:0] <= data_in; // sh
3'b010: MEM[address[ADDR_WIDTH - 1 : 2]] <= data_in; // sw
default: MEM[address[ADDR_WIDTH - 1 : 2]] <= data_in; // 默认sw
endcase
always_comb
if (read_en) // lw etc.
case (funct3)
3'b000: data_out = {{24{MEM[address[ADDR_WIDTH - 1 : 2]][7]}}, MEM[address[ADDR_WIDTH - 1 : 2]][7:0]}; // lb
3'b001: data_out = {{16{MEM[address[ADDR_WIDTH - 1 : 2]][15]}}, MEM[address[ADDR_WIDTH - 1 : 2]][15:0]}; // lh
3'b010: data_out = MEM[address[ADDR_WIDTH - 1 : 2]]; // lw
3'b100: data_out = {24'b0,MEM[address[ADDR_WIDTH - 1 : 2]][7:0]}; // lbu
3'b101: data_out = {16'b0,MEM[address[ADDR_WIDTH - 1 : 2]][15:0]}; // lhu
default: data_out = MEM[address[ADDR_WIDTH - 1 : 2]]; // 默认lw
endcase
endmodule

@ -0,0 +1,270 @@
`timescale 1ns / 1ps
// 数据通路
`include "pipeline_regs.sv"
import Pipe_Buf_Reg_PKG::*;
module Datapath #(
parameter PC_W = 9, // Program Counter
parameter INS_W = 32, // Instruction Width
parameter DATA_W = 32, // Data WriteData
parameter DM_ADDRESS = 9, // Data Memory Address
parameter ALU_CC_W = 4 // ALU Control Code Width
)(
input logic clock,
input logic reset, // reset , sets the PC to zero
input logic reg_write_en, // Register file writing enable
input logic MemtoReg, // Memory or ALU MUX
input logic alu_src, // Register file or Immediate MUX
input logic mem_write_en, // Memroy Writing Enable
input logic mem_read_en, // Memroy Reading Enable
input logic branch_taken, // Branch Enable
input logic jalr_sel, // Jalr Mux Select
input logic [1:0] alu_op,
input logic [1:0] RWSel, // Mux4to1 Select
input logic [ALU_CC_W -1:0] alu_cc, // ALU Control Code ( input of the ALU )
output logic [6:0] opcode,
output logic [6:0] funct7,
output logic [2:0] funct3,
output logic [1:0] aluop_current,
output logic [DATA_W-1:0] wb_data // data write back to register
);
// ====================================================================================
// Instruction Fetch (IF)
// ====================================================================================
//
// peripheral logic here.
//
logic BrFlush, stall;
logic [31:0] PC_mux_result, PC, PCplus4, BrPC, instr;
flipflop #(32) PC_unit(.clock(clock), .reset(reset), .d(PC_mux_result), .stall(stall), .q(PC));
mux2 PC_mux(.d0(PCplus4), .d1(BrPC), .s(BrFlush), .y(PC_mux_result));
adder #(32) PC_adder(.a(PC), .b(32'd4), .y(PCplus4));
//
// add your instruction memory
//
Insn_mem IM(.read_address(PC[PC_W - 1 : 0]), .insn(instr));
// ====================================================================================
// End of Instruction Fetch (IF)
// ====================================================================================
if_id_reg RegA;
id_ex_reg RegB;
ex_mem_reg RegC;
mem_wb_reg RegD;
always @(posedge clock, posedge reset)
begin
// add your logic here to update the IF_ID_Register
if (BrFlush | reset)
begin
RegA.Curr_Pc <= 9'b0;
RegA.Curr_Instr <= 32'b0;
end
else if (!stall)
begin
RegA.Curr_Pc <= PC[PC_W - 1 : 0];
RegA.Curr_Instr <= instr;
end
end
// ====================================================================================
// Instruction Decoding (ID)
// ====================================================================================
//
// peripheral logic here.
//
assign opcode = RegA.Curr_Instr[6:0];
logic [31:0] rd1, rd2, ImmG;
//
// add your register file here.
//
Reg_file RF(.clock(clock), .reset(reset), .write_en(RegD.RegWrite), .write_addr(RegD.rd),
.data_in(wb_data), .read_addr1(RegA.Curr_Instr[19:15]),
.read_addr2(RegA.Curr_Instr[24:20]), .data_out1(rd1), .data_out2(rd2));
//
// add your immediate generator here
//
Imm_gen Imm_Gen(.inst_code(RegA.Curr_Instr), .imm_out(ImmG));
// ====================================================================================
// End of Instruction Decoding (ID)
// ====================================================================================
always @(posedge clock, posedge reset)
begin
// add your logic here to update the ID_EX_Register
if (BrFlush | reset | stall)
begin
RegB.ALUSrc <= 1'b0;
RegB.MemtoReg <= 1'b0;
RegB.RegWrite <= 1'b0;
RegB.MemRead <= 1'b0;
RegB.MemWrite <= 1'b0;
RegB.ALUOp <= 2'b0;
RegB.Branch <= 1'b0;
RegB.JalrSel <= 1'b0;
RegB.RWSel <= 2'b0;
RegB.Curr_Pc <= 9'b0;
RegB.RD_One <= 32'b0;
RegB.RD_Two <= 32'b0;
RegB.RS_One <= 5'b0;
RegB.RS_Two <= 5'b0;
RegB.rd <= 5'b0;
RegB.ImmG <= 32'b0;
RegB.func3 <= 3'b0;
RegB.func7 <= 7'b0;
RegB.Curr_Instr <= 32'b0;
end
else if (!stall)
begin
RegB.ALUSrc <= alu_src;
RegB.MemtoReg <= MemtoReg;
RegB.RegWrite <= reg_write_en;
RegB.MemRead <= mem_read_en;
RegB.MemWrite <= mem_write_en;
RegB.ALUOp <= alu_op;
RegB.Branch <= branch_taken;
RegB.JalrSel <= jalr_sel;
RegB.RWSel <= RWSel;
RegB.Curr_Pc <= RegA.Curr_Pc;
RegB.RD_One <= rd1;
RegB.RD_Two <= rd2;
RegB.RS_One <= RegA.Curr_Instr[19:15];
RegB.RS_Two <= RegA.Curr_Instr[24:20];
RegB.rd <= RegA.Curr_Instr[11:7];
RegB.ImmG <= ImmG;
RegB.func3 <= RegA.Curr_Instr[14:12];
RegB.func7 <= RegA.Curr_Instr[31:25];
RegB.Curr_Instr <= RegA.Curr_Instr;
end
end
// ====================================================================================
// Execution (EX)
// ====================================================================================
//
// add your ALU, branch unit and with peripheral logic here
//
logic [31:0] FA_mux_result, FB_mux_result, ALU_result, PCplusImm, PCplus4_EX, src_mux_result, lui_mux_resultA, lui_mux_resultB;
logic [1:0] ForwardA, ForwardB;
logic zero, if_lui1, if_lui2;
assign aluop_current = RegB.ALUOp;
assign funct3 = RegB.func3;
assign funct7 = RegB.func7;
assign if_lui = (RegC.Curr_Instr[6:0] == 7'b0110111)? 1'b1 : 1'b0;
alu ALU(.operand_a(FA_mux_result), .operand_b(src_mux_result), .alu_ctrl(alu_cc), .alu_result(ALU_result), .zero(zero));
BranchUnit Branch_unit(.cur_pc(RegB.Curr_Pc), .imm(RegB.ImmG), .jalr_sel(RegB.JalrSel), .branch_taken(RegB.Branch),
.alu_result(ALU_result), .pc_plus_imm(PCplusImm), .pc_plus_4(PCplus4_EX), .branch_target(BrPC), .pc_sel(BrFlush));
mux4 FA_mux(.d00(RegB.RD_One), .d01(lui_mux_resultA), .d10(wb_data), .d11(32'b0), .s(ForwardA), .y(FA_mux_result));
mux4 FB_mux(.d00(RegB.RD_Two), .d01(lui_mux_resultB), .d10(wb_data), .d11(32'b0), .s(ForwardB), .y(FB_mux_result));
mux2 src_mux(.d0(FB_mux_result), .d1(RegB.ImmG), .s(RegB.ALUSrc), .y(src_mux_result));
mux2 lui_muxA(.d0(RegC.Alu_Result), .d1(RegC.Imm_Out), .s(if_lui), .y(lui_mux_resultA));
mux2 lui_muxB(.d0(RegC.Alu_Result), .d1(RegC.Imm_Out), .s(if_lui), .y(lui_mux_resultB));
// ====================================================================================
// End of Execution (EX)
// ====================================================================================
always @(posedge clock, posedge reset)
begin
// add your logic here to update the EX_MEM_Register
if(reset)
begin
RegC.RegWrite <= 1'b0;
RegC.MemtoReg <= 1'b0;
RegC.MemRead <= 1'b0;
RegC.MemWrite <= 1'b0;
RegC.RWSel <= 2'b0;
RegC.Pc_Imm <= 32'b0;
RegC.Pc_Four <= 32'b0;
RegC.Imm_Out <= 32'b0;
RegC.Alu_Result <= 32'b0;
RegC.RD_Two <= 32'b0;
RegC.rd <= 5'b0;
RegC.func3 <= 3'b0;
RegC.func7 <= 7'b0;
RegC.Curr_Instr <= 32'b0;
end
else
begin
RegC.RegWrite <= RegB.RegWrite;
RegC.MemtoReg <= RegB.MemtoReg;
RegC.MemRead <= RegB.MemRead;
RegC.MemWrite <= RegB.MemWrite;
RegC.RWSel <= RegB.RWSel;
RegC.Pc_Imm <= PCplusImm;
RegC.Pc_Four <= PCplus4_EX;
RegC.Imm_Out <= RegB.ImmG; // lui
RegC.Alu_Result <= ALU_result;
RegC.RD_Two <= FB_mux_result;
RegC.rd <= RegB.rd;
RegC.func3 <= RegB.func3;
RegC.func7 <= RegB.func7;
RegC.Curr_Instr <= RegB.Curr_Instr;
end
end
// ====================================================================================
// Memory Access (MEM)
// ====================================================================================
// add your data memory here.
logic [31:0] ReadData;
datamemory DM(.clock(clock), .read_en(RegC.MemRead), .write_en(RegC.MemWrite),
.address(RegC.Alu_Result[11:0]), .data_in(RegC.RD_Two), .funct3(RegC.func3), .data_out(ReadData));
// ====================================================================================
// End of Memory Access (MEM)
// ====================================================================================
always @(posedge clock)
begin
// add your logic here to update the MEM_WB_Register
if(reset)
begin
RegD.RegWrite <= 1'b0;
RegD.MemtoReg <= 1'b0;
RegD.RWSel <= 2'b0;
RegD.Pc_Imm <= 32'b0;
RegD.Pc_Four <= 32'b0;
RegD.Imm_Out <= 32'b0;
RegD.Alu_Result <= 32'b0;
RegD.MemReadData <= 32'b0;
RegD.rd <= 5'b0;
RegD.Curr_Instr <= 5'b0;
end
else
begin
RegD.RegWrite <= RegC.RegWrite;
RegD.MemtoReg <= RegC.MemtoReg;
RegD.RWSel <= RegC.RWSel;
RegD.Pc_Imm <= RegC.Pc_Imm;
RegD.Pc_Four <= RegC.Pc_Four;
RegD.Imm_Out <= RegC.Imm_Out;
RegD.Alu_Result <= RegC.Alu_Result;
RegD.MemReadData <= ReadData;
RegD.rd <= RegC.rd;
RegD.Curr_Instr <= RegC.Curr_Instr;
end
end
// ====================================================================================
// Write Back (WB)
// ====================================================================================
//
// add your write back logic here.
//
logic [31:0] res_mux_result;
mux2 res_mux(.d0(RegD.Alu_Result), .d1(RegD.MemReadData), .s(RegD.MemtoReg), .y(res_mux_result));
mux4 wrs_mux(.d00(res_mux_result), .d01(RegD.Pc_Four), .d10(RegD.Imm_Out), .d11(RegD.Pc_Imm), .s(RegD.RWSel), .y(wb_data));
// ====================================================================================
// End of Write Back (WB)
// ====================================================================================
// ====================================================================================
// other logic
// ====================================================================================
//
// add your hazard detection logic here
//
Hazard_detector hazard_unit(.clock(clock), .reset(reset), .if_id_rs1(RegA.Curr_Instr[19:15]), .if_id_rs2(RegA.Curr_Instr[24:20]),
.id_ex_rd(RegB.rd), .id_ex_memread(RegB.MemRead), .stall(stall));
//
// add your forwarding logic here
//
ForwardingUnit forwarding_unit(.rs1(RegB.RS_One), .rs2(RegB.RS_Two), .ex_mem_rd(RegC.rd), .mem_wb_rd(RegD.rd),
.ex_mem_regwrite(RegC.RegWrite), .mem_wb_regwrite(RegD.RegWrite), .forward_a(ForwardA), .forward_b(ForwardB));
//
// possible extra code
//
endmodule

@ -0,0 +1,35 @@
`timescale 1ns / 1ps
//////////////////////////////////////////////////////////////////////////////////
// Module Name: flipflop
// Description: An edge-triggered register
// When reset is `1`, the value of the register is set to 0.
// 当reset被置为1时重置该寄存器的信号为全0
// Otherwise:
// 否则
// - if stall is set, the register preserves its original data
// - else, it is updated by `d`.
// 如果stall被置为1寄存器保留原来的值stall被置为0将d的值写入寄存器
//////////////////////////////////////////////////////////////////////////////////
// 边沿触发寄存器
module flipflop # (
parameter WIDTH = 8
)(
input logic clock,
input logic reset,
input logic [WIDTH-1:0] d,
input logic stall,
output logic [WIDTH-1:0] q
);
always_ff @(posedge clock, posedge reset)
begin
if (reset)
q <= 0;
else if (!stall)
q <= d;
end
endmodule

@ -0,0 +1,32 @@
`timescale 1ns / 1ps
// 数据定向处理单元
module ForwardingUnit (
input logic [4:0] rs1,
input logic [4:0] rs2,
input logic [4:0] ex_mem_rd,
input logic [4:0] mem_wb_rd,
input logic ex_mem_regwrite,
input logic mem_wb_regwrite,
output logic [1:0] forward_a,
output logic [1:0] forward_b
);
// define your forwarding logic here.
always_comb
begin
if ((rs1 != 0) && (rs1 == ex_mem_rd) && ex_mem_regwrite)
forward_a = 2'b01;
else if ((rs1 != 0) && (rs1 == mem_wb_rd) && mem_wb_regwrite)
forward_a = 2'b10;
else
forward_a = 2'b00;
if ((rs2 != 0) && (rs2 == ex_mem_rd) && ex_mem_regwrite)
forward_b = 2'b01;
else if ((rs2 != 0) && (rs2 == mem_wb_rd) && mem_wb_regwrite)
forward_b = 2'b10;
else
forward_b = 2'b00;
end
endmodule

@ -0,0 +1,35 @@
`timescale 1ns / 1ps
// 冒险探测器(阻塞生成器)
module Hazard_detector (
input logic clock,
input logic reset,
input logic [4:0] if_id_rs1,
input logic [4:0] if_id_rs2,
input logic [4:0] id_ex_rd,
input logic id_ex_memread,
output logic stall
);
// define your hazard detection logic here
logic [1:0] counter;
always @(negedge clock)
begin
if (reset)
begin
stall <= 1'b0;
counter <= 2'b00;
end
else
begin
stall <= (id_ex_memread && ((id_ex_rd == if_id_rs1) || (id_ex_rd == if_id_rs2)));
if (stall == 1'b1)
counter <= counter + 2'b01;
if (counter == 2'b10)
begin
counter <= 2'b00;
stall <= 1'b0;
end
end
end
endmodule

@ -0,0 +1,23 @@
`timescale 1ns / 1ps
// 立即数扩展
module Imm_gen(
input logic [31:0] inst_code,
output logic [31:0] imm_out
);
// add your immediate extension logic here.
logic [6:0] test;
assign test = inst_code[6:0];
always_comb
case (test)
7'b0010011: imm_out = {{20{inst_code[31]}}, inst_code[31:20]}; // andi, ori, addi
7'b0000011: imm_out = {{20{inst_code[31]}}, inst_code[31:20]}; // lb, lh, lw, lbu, lhu
7'b0100011: imm_out = {{20{inst_code[31]}}, inst_code[31:25], inst_code[11:7]}; // sb, sh, sw
7'b1100011: imm_out = {{20{inst_code[31]}}, inst_code[31], inst_code[7], inst_code[30:25], inst_code[11:8]}; // beq, bne, blt, bge, bltu, bgeu
7'b1101111: imm_out = {{12{inst_code[31]}}, inst_code[31], inst_code[19:12], inst_code[20], inst_code[30:21]}; // jal
7'b1100111: imm_out = {{20{inst_code[31]}}, inst_code[31:20]}; // jalr
7'b0110111: imm_out = {inst_code[31:12], 12'b0}; // lui
default: imm_out = 32'd0;
endcase
endmodule

@ -0,0 +1,22 @@
`timescale 1ns / 1ps
//////////////////////////////////////////////////////////////////////////////////
// 指令存储<E5AD98>?
module Insn_mem #(
parameter ADDR_WIDTH = 9,
parameter INSN_WIDTH = 32
)(
input logic [ADDR_WIDTH - 1 : 0] read_address,
output logic [INSN_WIDTH - 1 : 0] insn
);
logic [INSN_WIDTH-1 :0] insn_array [(2**(ADDR_WIDTH - 2))-1:0];
initial begin
$display("reading from insn.txt...");
$readmemh("insn.txt", insn_array);
$display("finished reading from insn.txt...");
end
assign insn = insn_array[read_address[ADDR_WIDTH - 1 : 2]];
endmodule

@ -0,0 +1,13 @@
`timescale 1ns / 1ps
// 二端口多路选择器
module mux2 #(
parameter WIDTH = 32
)(
input logic [WIDTH-1:0] d0, d1,
input logic s,
output logic [WIDTH-1:0] y
);
assign y = s ? d1 : d0;
endmodule

@ -0,0 +1,13 @@
`timescale 1ns / 1ps
// 四端口多路选择器
module mux4 #(
parameter WIDTH = 32
)(
input logic [WIDTH-1:0] d00, d01, d10, d11,
input logic [1:0] s,
output logic [WIDTH-1:0] y
);
assign y = (s==2'b11) ? d11 : (s==2'b10) ? d10 : (s==2'b01) ? d01 : d00;
endmodule

@ -0,0 +1,63 @@
//
package Pipe_Buf_Reg_PKG;
// Reg A
typedef struct packed{
logic [8:0] Curr_Pc;
logic [31:0] Curr_Instr;
} if_id_reg;
// Reg B
typedef struct packed{
logic ALUSrc;
logic MemtoReg;
logic RegWrite;
logic MemRead;
logic MemWrite;
logic [1:0] ALUOp;
logic Branch;
logic JalrSel;
logic [1:0] RWSel;
logic [8:0] Curr_Pc;
logic [31:0] RD_One;
logic [31:0] RD_Two;
logic [4:0] RS_One;
logic [4:0] RS_Two;
logic [4:0] rd;
logic [31:0] ImmG;
logic [2:0] func3;
logic [6:0] func7;
logic [31:0] Curr_Instr;
} id_ex_reg;
// Reg C
typedef struct packed{
logic RegWrite;
logic MemtoReg;
logic MemRead;
logic MemWrite;
logic [1:0] RWSel;
logic [31:0] Pc_Imm;
logic [31:0] Pc_Four;
logic [31:0] Imm_Out;
logic [31:0] Alu_Result;
logic [31:0] RD_Two;
logic [4:0] rd;
logic [2:0] func3;
logic [6:0] func7;
logic [31:0] Curr_Instr;
} ex_mem_reg;
// Reg D
typedef struct packed{
logic RegWrite;
logic MemtoReg;
logic [1:0] RWSel;
logic [31:0] Pc_Imm;
logic [31:0] Pc_Four;
logic [31:0] Imm_Out;
logic [31:0] Alu_Result;
logic [31:0] MemReadData;
logic [4:0] rd;
logic [31:0] Curr_Instr;
} mem_wb_reg;
endpackage

@ -0,0 +1,37 @@
`timescale 1ns / 1ps
// 主控制器
module Proc_controller(
//Input
input logic [6:0] Opcode, //7-bit opcode field from the instruction
//Outputs
output logic ALUSrc, //0: The second ALU operand comes from the second register file output (Read data 2);
//1: The second ALU operand is the sign-extended, lower 16 bits of the instruction.
output logic MemtoReg, //0: The value fed to the register Write data input comes from the ALU.
//1: The value fed to the register Write data input comes from the data memory.
output logic RegWrite, //The register on the Write register input is written with the value on the Write data input
output logic MemRead, //Data memory contents designated by the address input are put on the Read data output
output logic MemWrite, //Data memory contents designated by the address input are replaced by the value on the Write data input.
output logic [1:0] ALUOp, //00: LW/SW/AUIPC; 01:Branch; 10: Rtype/Itype; 11:JAL/LUI
output logic Branch, //0: branch is not taken; 1: branch is taken
output logic JalrSel, //0: Jalr is not taken; 1: jalr is taken
output logic [1:0] RWSel //00Register Write Back; 01: PC+4 write back(JAL/JALR); 10: imm-gen write back(LUI); 11: pc+imm-gen write back(AUIPC)
);
logic [10:0] con;
always_comb
case (Opcode)
7'b0110011: con = 11'b0_0_1_0_0_10_0_0_00; // R-type
7'b0110111: con = 11'b0_0_1_0_0_00_0_0_10; // lui
7'b1101111: con = 11'b1_0_1_0_0_11_1_0_01; // jal
7'b0010011: con = 11'b1_0_1_0_0_10_0_0_00; // I-type1 (includes ori, andi, addi)
7'b0000011: con = 11'b1_1_1_1_0_00_0_0_00; // I-type2 (includes lb, lh, lw, lbu, lhu)
7'b1100111: con = 11'b1_0_1_0_0_10_1_1_01; // I-type3 (jalr)
7'b0100011: con = 11'b1_0_0_0_1_00_0_0_00; // S-type1 (includes sb, sh, sw)
7'b1100011: con = 11'b0_0_0_0_0_01_1_0_00; // S-type2 (includes beq, bne, blt, bge, bltu, bgeu)
default: con = 11'b0_0_0_0_0_00_0_0_00;
endcase
assign {ALUSrc, MemtoReg, RegWrite, MemRead, MemWrite, ALUOp, Branch, JalrSel, RWSel} = con;
endmodule

@ -0,0 +1,54 @@
`timescale 1ns / 1ps
// 寄存器文件
module Reg_file #(
parameter DATA_WIDTH = 32, // number of bits in each register
parameter ADDRESS_WIDTH = 5, //number of registers = 2^ADDRESS_WIDTH
parameter NUM_REGS = 2 ** ADDRESS_WIDTH
)(
// Inputs
input clock, //clock
input reset, //synchronous reset; reset all regs to 0 upon assertion.
input write_en, //write enable
input [ADDRESS_WIDTH-1:0] write_addr, //address of the register that supposed to written into
input [DATA_WIDTH-1:0] data_in, // data that supposed to be written into the register file
input [ADDRESS_WIDTH-1:0] read_addr1, //first address to be read from
input [ADDRESS_WIDTH-1:0] read_addr2, //second address to be read from
// Outputs
output logic [DATA_WIDTH-1:0] data_out1, //content of reg_file[read_addr1] is loaded into
output logic [DATA_WIDTH-1:0] data_out2 //content of reg_file[read_addr2] is loaded into
);
integer i;
logic [DATA_WIDTH-1:0] register_file [NUM_REGS-1:0];
integer log_file;
initial begin
log_file = $fopen("./reg_trace.txt", "w");
if (log_file)
$display("***************************** File was opened succussfully: %s", "./test.txt");
else
$display("***************************** Failed to open the file: %s", "./test.txt");
end
always @( negedge clock )
begin
if( reset == 1'b1 )
for (i = 0; i < NUM_REGS ; i = i + 1) begin
register_file [i] <= 0;
$fwrite(log_file, "r%d, 0", i);
end
else if( reset ==1'b0 && write_en ==1'b1 && write_addr != 0) begin
register_file [ write_addr ] <= data_in;
$fwrite(log_file, "r%02x, %08x\n", write_addr, data_in);
end
end
assign data_out1 = register_file[read_addr1];
assign data_out2 = register_file[read_addr2];
endmodule

@ -0,0 +1,25 @@
`timescale 1ns / 1ps
// risc-V整体模块
module riscv #(
parameter DATA_W = 32)
(input logic clock, reset, // clock and reset signals
output logic [31:0] WB_Data// The ALU_Result
);
logic [6:0] opcode;
logic ALUSrc, MemtoReg, RegWrite, MemRead, MemWrite, Branch, JalrSel;
logic [1:0] RWSel;
logic [1:0] ALUop;
logic [1:0] ALUop_Reg;
logic [6:0] Funct7;
logic [2:0] Funct3;
logic [3:0] Operation;
Proc_controller proc_controller(opcode, ALUSrc, MemtoReg, RegWrite, MemRead, MemWrite, ALUop, Branch, JalrSel, RWSel);
ALU_Controller proc_alu_controller(ALUop_Reg, Funct7, Funct3, Operation);
Datapath proc_data_path(clock, reset, RegWrite , MemtoReg, ALUSrc , MemWrite, MemRead, Branch, JalrSel, ALUop, RWSel, Operation, opcode, Funct7, Funct3, ALUop_Reg, WB_Data);
endmodule

@ -0,0 +1,30 @@
`timescale 1ns / 1ps
//
module tb_top;
//clock and reset signal declaration
logic tb_clk, reset;
logic [31:0] tb_WB_Data;
//clock generation
always #10 tb_clk = ~tb_clk;
//reset Generation
initial begin
tb_clk = 0;
reset = 1;
#25 reset =0;
end
riscv riscV(
.clock(tb_clk),
.reset(reset),
.WB_Data(tb_WB_Data)
);
initial begin
#2500;
$finish;
end
endmodule
Loading…
Cancel
Save