OpenCores
URL https://opencores.org/ocsvn/zap/zap/trunk

Subversion Repositories zap

Compare Revisions

  • This comparison shows the changes necessary to convert path
    /
    from Rev 50 to Rev 51
    Reverse comparison

Rev 50 → Rev 51

/zap/trunk/src/rtl/cpu/zap_alu_main.v
159,18 → 159,18
// Memory access related
// ----------------------------------------------------------------
 
output reg [zap_clog2(PHY_REGS)-1:0] o_mem_srcdest_index_ff, // LD/ST data register.
output reg o_mem_load_ff, // LD/ST load indicator.
output reg o_mem_store_ff, // LD/ST store indicator.
output reg [31:0] o_mem_address_ff, // LD/ST address to access.
output reg o_mem_unsigned_byte_enable_ff, // uint8_t
output reg o_mem_signed_byte_enable_ff, // int8_t
output reg o_mem_signed_halfword_enable_ff, // int16_t
output reg o_mem_unsigned_halfword_enable_ff, // uint16_t
output reg [31:0] o_mem_srcdest_value_ff, // LD/ST value to store.
output reg o_mem_translate_ff, // LD/ST force user view of memory.
output reg [3:0] o_ben_ff, // LD/ST byte enables (only for STore instructions).
output reg [31:0] o_address_nxt, // D pin of address register to drive TAG RAMs.
output reg [zap_clog2(PHY_REGS)-1:0] o_mem_srcdest_index_ff, // LD/ST data register.
output reg o_mem_load_ff, // LD/ST load indicator.
output reg o_mem_store_ff, // LD/ST store indicator.
output reg [31:0] o_mem_address_ff, // LD/ST address to access.
output reg o_mem_unsigned_byte_enable_ff, // uint8_t
output reg o_mem_signed_byte_enable_ff, // int8_t
output reg o_mem_signed_halfword_enable_ff, // int16_t
output reg o_mem_unsigned_halfword_enable_ff, // uint16_t
output reg [31:0] o_mem_srcdest_value_ff, // LD/ST value to store.
output reg o_mem_translate_ff, // LD/ST force user view of memory.
output reg [3:0] o_ben_ff, // LD/ST byte enables (only for STore instructions).
output reg [31:0] o_address_nxt, // D pin of address register to drive TAG RAMs.
 
// -------------------------------------------------------------
// Wishbone signal outputs.
200,10 → 200,7
// Localparams
// -----------------------------------------------------------------------------
 
/*
* These override global N,Z,C,V definitions which are on CPSR. These params
* are localized over the 4-bit flag structure.
*/
// Local N,Z,C,V structures.
localparam [1:0] _N = 2'd3;
localparam [1:0] _Z = 2'd2;
localparam [1:0] _C = 2'd1;
451,7 → 448,7
o_data_wb_sel_nxt = o_data_wb_sel_ff;
o_address_nxt = o_mem_address_ff;
 
if ( i_reset )
if ( i_reset ) // Synchronous reset.
begin
o_data_wb_cyc_nxt = 1'd0;
o_data_wb_stb_nxt = 1'd0;
650,8 → 647,6
begin
if ( i_flag_update_ff && o_dav_nxt ) // PC update with S bit. Context restore.
begin
$display($time, " - %m :: Saw PC update with S bit set. Context restore initiated.");
 
o_destination_index_nxt = PHY_RAZ_REGISTER;
o_clear_from_alu = 1'd1;
o_pc_from_alu = tmp_sum;
671,11 → 666,6
if ( i_switch_ff )
begin
flags_nxt[T] = tmp_sum[0];
 
if ( tmp_sum[0] )
$display($time, " - %m :: Entering T state.");
else
$display($time, " - %m :: Entering A state.");
end
end
else // Correctly predicted.
690,11 → 680,6
o_clear_from_alu = 1'd1;
o_pc_from_alu = tmp_sum; // Jump to branch target.
flags_nxt[T] = tmp_sum[0];
if ( tmp_sum[0] )
$display($time, " - %m :: Entering T state.");
else
$display($time, " - %m :: Entering A state.");
end
else
begin
713,10 → 698,13
else // Branch not taken
begin
if ( i_taken_ff == WT || i_taken_ff == ST )
//
// Wrong prediction as taken. Go back to the same
// branch. Non branches are always predicted as not-taken.
//
// GO BACK TO THE SAME BRANCH AND INFORM PREDICTOR OF ITS
// MISTAKE - THE NEXT TIME THE PREDICTION WILL BE NOT-TAKEN.
//
begin
o_clear_from_alu = 1'd1;
o_pc_from_alu = i_pc_ff;
731,7 → 719,6
else if ( i_mem_srcdest_index_ff == ARCH_PC && o_dav_nxt && i_mem_load_ff)
begin
// Loads to PC also puts the unit to sleep.
$display($time, " - %m :: ALU saw a load to R15. Sleeping to prevent further instructions from executing.");
sleep_nxt = 1'd1;
end
 
947,26 → 934,24
end
endfunction // generate_ben
 
// assertions_start
 
/*
* This assertion ensures that no privilege escalation is possible.
* It does so by ensuring that the flag register cannot change out
* of USR during normal operation.
*/
always @*
/*
* This assertion ensures that no privilege escalation is possible.
* It does so by ensuring that the flag register cannot change out
* of USR during normal operation.
*/
always @*
begin
if ( flags_nxt[`CPSR_MODE] != USR && flags_ff[`CPSR_MODE] == USR )
begin
if ( flags_nxt[`CPSR_MODE] != USR && flags_ff[`CPSR_MODE] == USR )
begin
$display($time, " - %m :: Error: Privilege Escalation Error.");
$stop;
end
$display($time, " - %m :: Error: Privilege Escalation Error.");
$stop;
end
end
 
reg [64*8-1:0] OPCODE;
always @*
case(opcode)
reg [64*8-1:0] OPCODE;
 
always @*
case(opcode)
AND:begin OPCODE = "AND"; end
EOR:begin OPCODE = "EOR"; end
MOV:begin OPCODE = "MOV"; end
985,10 → 970,12
RSC:begin OPCODE = "RSC"; end
CMP:begin OPCODE = "CMP"; end
CMN:begin OPCODE = "CMN"; end
endcase
endcase
 
// assertions_end
 
endmodule // zap_alu_main.v
 
`default_nettype wire
 
// ----------------------------------------------------------------------------
// END OF FILE
// ----------------------------------------------------------------------------
/zap/trunk/src/rtl/cpu/zap_cache.v
321,7 → 321,7
o_wb_wen_nxt = wb_wen[state_nxt];
end
 
// assertions_start
// synopsys translate_off
reg xerr = 0;
always @ (posedge i_clk)
329,12 → 329,12
// Check if data delivered to processor is 'x'.
if ( o_dat[0] === 1'dx && o_ack && i_rd )
begin
xerr = xerr + 1;
$display($time, "Error : %m Data went to x when giving data to core.");
xerr = xerr + 1;
$stop;
end
end
// assertions_end
// synopsys translate_on
 
endmodule // zap_cache
 
/zap/trunk/src/rtl/cpu/zap_cache_fsm.v
124,16 → 124,16
localparam CLEAN = 7; /* Cache clean parent state */
localparam NUMBER_OF_STATES = 8;
 
// ---------------------------------------------------------------
// ----------------------------------------------------------------------------
// Signal aliases
// ---------------------------------------------------------------
// ----------------------------------------------------------------------------
 
wire cache_cmp = (i_cache_tag[`CACHE_TAG__TAG] == i_address[`VA__CACHE_TAG]);
wire cache_dirty = i_cache_tag_dirty;
 
// ---------------------------------------------------------------
// ----------------------------------------------------------------------------
// Variables
// ---------------------------------------------------------------
// ----------------------------------------------------------------------------
 
reg [$clog2(NUMBER_OF_STATES)-1:0] state_ff, state_nxt;
reg [31:0] buf_ff [3:0];
145,13 → 145,13
reg [2:0] adr_ctr_ff, adr_ctr_nxt; // Needs to take on 0,1,2,3 AND 4(nxt).
reg hit; // For debug only.
 
// ----------------------------------------------------------------
// ----------------------------------------------------------------------------
// Logic
// ----------------------------------------------------------------
// ----------------------------------------------------------------------------
 
/* Tie flops to the output */
always @* o_cache_clean_req = cache_clean_req_ff; // Tie req flop to output.
always @* o_cache_inv_req = cache_inv_req_ff; // Tie inv flop to output.
always @* o_cache_inv_req = cache_inv_req_ff; // Tie inv flop to output.
 
/* Sequential Block */
always @ (posedge i_clk)
469,9 → 469,9
endcase
end
 
// ------------------------------------------------------------------------
// ----------------------------------------------------------------------------
// Tasks and functions.
// ------------------------------------------------------------------------
// ----------------------------------------------------------------------------
 
function [31:0] adapt_cache_data
(input [1:0] shift, input [127:0] cd);
503,8 → 503,6
input [31:0] i_address;
input [2:0] i_cti;
begin
$display($time, " - %m :: Reading from address %x", i_address);
 
o_wb_cyc_nxt = 1'd1;
o_wb_stb_nxt = 1'd1;
o_wb_wen_nxt = 1'd0;
522,8 → 520,6
input [2:0] i_cti;
input [3:0] i_ben;
begin
$display($time, " - %m :: Writing to address %x with ben = %x", i_address, i_ben);
 
o_wb_cyc_nxt = 1'd1;
o_wb_stb_nxt = 1'd1;
o_wb_wen_nxt = 1'd1;
549,8 → 545,6
 
// ----------------------------------------------------------------------------
 
// synopsys translate_off
wire [31:0] buf0_ff, buf1_ff, buf2_ff;
 
assign buf0_ff = buf_ff[0];
568,8 → 562,10
wire [31:0] dbg_ct_tag = o_cache_tag[`CACHE_TAG__TAG];
wire [31:0] dbg_ct_pa = o_cache_tag[`CACHE_TAG__PA];
 
// synopsys translate_on
 
endmodule // zap_cache_fsm
 
`default_nettype wire
 
// ----------------------------------------------------------------------------
// END OF FILE
// ----------------------------------------------------------------------------
/zap/trunk/src/rtl/cpu/zap_cache_tag_ram.v
26,11 → 26,12
// -- avoid translation during clean operations. The cache data RAM is also --
// -- present in this unit. This unit has a dedicated memory interface --
// -- because it can perform global clean and flush by itself without --
// -- depending on the cache controller. --
// -- depending on the cache controller. Only for FPGA. --
// -- --
// -----------------------------------------------------------------------------
 
`default_nettype none
 
`include "zap_defines.vh"
 
module zap_cache_tag_ram #(
265,18 → 266,6
tag_ram_wr_en = 0;
blk_ctr_nxt = 0;
 
// assertions_start
 
$display($time, " - %m :: Cache clean requested...");
 
for(i=0;i<CACHE_SIZE/16;i=i+1)
begin
$display($time, " - %m :: Line %d : %x %d", i, dat_ram[i], dirty[i]);
end
 
// assertions_end
 
 
state_nxt = CACHE_CLEAN_GET_ADDRESS;
end
else if ( i_cache_inv_req )
404,8 → 393,6
input [31:0] i_address;
input [2:0] i_cti;
begin
$display($time, " - %m :: Reading from address %x", i_address);
 
o_wb_cyc_nxt = 1'd1;
o_wb_stb_nxt = 1'd1;
o_wb_wen_nxt = 1'd0;
462,4 → 449,10
endfunction
 
endmodule // zap_cache_tag_ram.v
 
`default_nettype wire
 
// ----------------------------------------------------------------------------
// END OF FILE
// ----------------------------------------------------------------------------
 
/zap/trunk/src/rtl/cpu/zap_core.v
1192,7 → 1192,10
default: CPU_MODE = "???";
endcase
 
 
endmodule // zap_core.v
 
`default_nettype wire
 
// ----------------------------------------------------------------------------
// EOF
// ----------------------------------------------------------------------------
/zap/trunk/src/rtl/cpu/zap_cp15_cb.v
525,15 → 525,18
end
endtask
 
// assertions_start
wire [31:0] r0 = r[0];
wire [31:0] r1 = r[1];
wire [31:0] r2 = r[2];
wire [31:0] r3 = r[3];
wire [31:0] r4 = r[4];
wire [31:0] r5 = r[5];
wire [31:0] r6 = r[6];
// assertions_end
wire [31:0] r0 = r[0];
wire [31:0] r1 = r[1];
wire [31:0] r2 = r[2];
wire [31:0] r3 = r[3];
wire [31:0] r4 = r[4];
wire [31:0] r5 = r[5];
wire [31:0] r6 = r[6];
 
endmodule
 
`default_nettype wire
 
// ----------------------------------------------------------------------------
// EOF
// ----------------------------------------------------------------------------
/zap/trunk/src/rtl/cpu/zap_decode.v
124,55 → 124,6
localparam [1:0] UNSIGNED_HALF_WORD = 2'd1;
localparam [1:0] SIGNED_HALF_WORD = 2'd2;
 
// assertions_start
 
// Debug only.
reg bx, dp, br, mrs, msr, ls, mult, halfword_ls, swi, dp1, dp2, dp3, lmult, clz;
always @*
begin
bx = 0;
dp = 0;
br = 0;
mrs = 0;
msr = 0;
ls = 0;
mult = 0;
halfword_ls = 0;
swi = 0;
dp1 = 0;
dp2 = 0;
dp3 = 0;
//
// Debugging purposes.
//
if ( i_instruction_valid )
casez ( i_instruction[31:0] )
CLZ_INSTRUCTION: clz = 1;
BX_INST: bx = 1;
MRS: mrs = 1;
MSR,MSR_IMMEDIATE: msr = 1;
DATA_PROCESSING_IMMEDIATE,
DATA_PROCESSING_REGISTER_SPECIFIED_SHIFT,
DATA_PROCESSING_INSTRUCTION_SPECIFIED_SHIFT: dp = 1;
BRANCH_INSTRUCTION: br = 1;
LS_INSTRUCTION_SPECIFIED_SHIFT,LS_IMMEDIATE:
begin
if ( i_instruction[20] )
ls = 1; // Load
else
ls = 2; // Store
end
MULT_INST: mult = 1;
LMULT_INST: lmult = 1;
HALFWORD_LS: halfword_ls = 1;
SOFTWARE_INTERRUPT: swi = 1;
endcase
end
 
// assertions_end
 
// ----------------------------------------------------------------------------
 
always @*
298,9 → 249,6
 
o_shift_length[32] = i_instruction[24] ? INDEX_EN:IMMED_EN;
 
`ifdef DECODE_DEBUG
$display($time, "Long multiplication detected!");
`endif
 
// We need to generate output code.
case ( i_instruction[22:21] )
456,9 → 404,6
task decode_mult( input [34:0] i_instruction );
begin: tskDecodeMult
 
`ifdef DECODE_DEBUG
$display($time, "%m: MLT 32x32 -> 32 decode...");
`endif
 
o_condition_code = i_instruction[31:28];
o_flag_update = i_instruction[20];
524,9 → 469,6
task decode_ls( input [34:0] i_instruction );
begin: tskDecodeLs
 
`ifdef DECODE_DEBUG
$display($time, "%m: LS decode...");
`endif
 
o_condition_code = i_instruction[31:28];
 
690,8 → 632,6
//
task process_immediate ( input [34:0] instruction );
begin
dp1 = 1;
 
o_shift_length = instruction[11:8] << 1'd1;
o_shift_length[32] = IMMED_EN;
o_shift_source = instruction[7:0];
708,8 → 648,6
//
task process_instruction_specified_shift ( input [34:0] instruction );
begin
dp2 = 1;
 
// ROR #0 = RRC, ASR #0 = ASR #32, LSL #0 = LSL #0, LSR #0 = LSR #32
// ROR #n = ROR_1 #n ( n > 0 )
o_shift_length = instruction[11:7];
744,12 → 682,6
// The source register and the amount of shift are both in registers.
task process_register_specified_shift ( input [34:0] instruction );
begin
`ifdef DECODE_DEBUG
$display("%m Process register specified shift...");
`endif
 
dp3 = 1;
 
o_shift_length = instruction[11:8];
o_shift_length[32] = INDEX_EN;
o_shift_source = {i_instruction[`DP_RB_EXTEND], instruction[`DP_RB]};
/zap/trunk/src/rtl/cpu/zap_decompile.v
469,3 → 469,7
endmodule // zap_decompile.v
 
`default_nettype wire
 
// ----------------------------------------------------------------------------
// EOF
// ----------------------------------------------------------------------------
/zap/trunk/src/rtl/cpu/zap_fetch_main.v
295,7 → 295,7
assign _unused_ok_ = i_pc_from_alu[0] &&
i_pc_from_alu[31:$clog2(BP_ENTRIES) + 1];
 
// ---------------------------------------------------------------------------------
// ----------------------------------------------------------------------------
 
zap_decompile u_zap_decompile (
.i_instruction ({4'd0, o_instruction}),
306,3 → 306,7
 
endmodule // zap_fetch_main.v
`default_nettype wire
 
// ----------------------------------------------------------------------------
// EOF
// ----------------------------------------------------------------------------
/zap/trunk/src/rtl/cpu/zap_issue_main.v
501,32 → 501,19
 
begin
 
`ifdef ISSUE_DEBUG
$display($time, "Received index as %d and rd_port %d", index, rd_port);
`endif
 
if ( index[32] ) // Catch constant here.
begin
`ifdef ISSUE_DEBUG
$display($time, "Constant detect. Returning %x", index[31:0]);
`endif
 
get = index[31:0];
end
else if ( index == PHY_RAZ_REGISTER ) // Catch RAZ here.
begin
// Return 0.
`ifdef ISSUE_DEBUG
$display($time, "RAZ returned 0...");
`endif
get = 32'd0;
end
else if ( index == ARCH_PC ) // Catch PC here. ARCH index = PHY index so no problem.
begin
get = i_pc_plus_8_ff;
`ifdef ISSUE_DEBUG
$display($time, "PC requested... given as %x", get);
`endif
end
else if ( index == PHY_CPSR ) // Catch CPSR here.
begin
537,9 → 524,6
else if ( index == i_shifter_destination_index_ff && i_alu_dav_nxt )
begin // ALU effectively never changes destination so no need to look at _nxt.
get = i_alu_destination_value_nxt;
`ifdef ISSUE_DEBUG
$display($time, "Matched shifter destination index %x ... given as %x", i_shifter_destination_index_ff, get);
`endif
end
 
// Match in output of ALU stage.
546,9 → 530,6
else if ( index == i_alu_destination_index_ff && i_alu_dav_ff )
begin
get = i_alu_destination_value_ff;
`ifdef ISSUE_DEBUG
$display($time, "Matched ALU destination index %x ... given as %x", i_alu_destination_index_ff, get);
`endif
end
 
// Match in output of memory stage.
555,16 → 536,9
else if ( index == i_memory_destination_index_ff && i_memory_dav_ff )
begin
get = i_memory_destination_value_ff;
`ifdef ISSUE_DEBUG
$display($time, "Matched memory destination index %x ... given as %x", i_memory_destination_index_ff, get);
`endif
end
else // Index not found in the pipeline, fallback to register access.
begin
`ifdef ISSUE_DEBUG
$display($time, "Register read on rd_port %x", rd_port );
`endif
case ( rd_port )
0: get = i_rd_data_0;
1: get = i_rd_data_1;
571,18 → 545,11
2: get = i_rd_data_2;
3: get = i_rd_data_3;
endcase
`ifdef ISSUE_DEBUG
$display($time, "Reg read -> Returned value %x", get);
`endif
end
 
// The memory accelerator. If the required stuff is present in the memory unit, short circuit.
if ( index == i_memory_mem_srcdest_index_ff && i_memory_mem_load_ff && i_memory_dav_ff )
begin
`ifdef ISSUE_DEBUG
$display($time, "Memory accelerator gets value %x", i_memory_mem_srcdest_value_ff);
`endif
 
get = i_memory_mem_srcdest_value_ff;
end
 
769,4 → 736,9
endfunction
 
endmodule // zap_issue_main.v
 
`default_nettype wire
 
// ----------------------------------------------------------------------------
// EOF
// ----------------------------------------------------------------------------
/zap/trunk/src/rtl/cpu/zap_predecode_compress.v
117,9 → 117,6
T_MOD_SP : decode_mod_sp;
default:
begin
`ifdef COMP_DEBUG
$display($time, "%m: Not implemented in compressed decoder!!!");
`endif
o_und = 1; // Will take UND trap.
end
endcase
360,7 → 357,7
2: o_instruction[31:0] = {AL, 2'b00, 1'b0, MOV, 1'b0, rd, rd, 8'd0, rs}; // MOV Rd, Rs
3:
begin
$display($time, "%m: This should never happen, should be taken by BX...!");
$display($time, "%m: Error: This should never happen, should be taken by BX...!");
$finish;
end
endcase
/zap/trunk/src/rtl/cpu/zap_predecode_coproc.v
27,6 → 27,7
// ----------------------------------------------------------------------------
 
`default_nettype none
 
module zap_predecode_coproc #(
parameter PHY_REGS = 46
)
275,4 → 276,9
endtask
 
endmodule
 
`default_nettype wire
 
// ----------------------------------------------------------------------------
// EOF
// ----------------------------------------------------------------------------
/zap/trunk/src/rtl/cpu/zap_predecode_mem_fsm.v
228,8 → 228,6
// Immediate Offset.
if ( i_instruction[31:25] == BLX1[31:25] && i_instruction_valid )
begin
$display($time, "%m: BLX1 detected!");
 
// We must generate a SUBAL LR,PC,4 ROR 0
// This makes LR have the value
// PC+8-4=PC+4 which is the address of
247,8 → 245,6
end
else if ( i_instruction[27:4] == BLX2[27:4] && i_instruction_valid ) // BLX2 detected. Register offset. CONDITIONAL.
begin
$display($time, "%m: BLX2 detected!");
 
// Write address of next instruction to LR. Now this
// depends on the mode we're in. Mode in the sense
// ARM/Thumb. We need to look at i_cpsr_t.
273,10 → 269,6
begin
// Backup base register.
// MOV DUMMY0, Base
`ifdef LDM_DEBUG
$display($time, "%m: Load/Store Multiple detected!");
`endif
if ( up )
begin
o_instruction = {cc, 2'b00, 1'b0, MOV,
314,9 → 306,6
i_instruction[11:4] == 4'b1001 && i_instruction_valid ) // SWAP
begin
// Swap
`ifdef LDM_DEBUG
$display($time, "%m: Detected SWAP instruction!");
`endif
 
o_irq = i_irq;
o_fiq = i_fiq;
/zap/trunk/src/rtl/cpu/zap_ram_simple.v
22,7 → 22,7
// -----------------------------------------------------------------------------
// -- --
// -- Synthesizes to standard 1R + 1W block RAM. The read and write addresses--
// -- may be specified separately. --
// -- may be specified separately. Only for FPGA. --
// -- --
// -----------------------------------------------------------------------------
 
75,4 → 75,9
end
 
endmodule // ram_simple.v
 
`default_nettype wire
 
// ----------------------------------------------------------------------------
// EOF
// ----------------------------------------------------------------------------
/zap/trunk/src/rtl/cpu/zap_register_file.v
70,48 → 70,46
 
reg [39:0] sel;
 
// assertions_start
wire [31:0] r0; assign r0 = sel[0] ? MEM[0] : mem[0];
wire [31:0] r1; assign r1 = sel[1] ? MEM[1] : mem[1];
wire [31:0] r2; assign r2 = sel[2] ? MEM[2] : mem[2];
wire [31:0] r3; assign r3 = sel[3] ? MEM[3] : mem[3];
wire [31:0] r4; assign r4 = sel[4] ? MEM[4] : mem[4];
wire [31:0] r5; assign r5 = sel[5] ? MEM[5] : mem[5];
wire [31:0] r6; assign r6 = sel[6] ? MEM[6] : mem[6];
wire [31:0] r7; assign r7 = sel[7] ? MEM[7] : mem[7];
wire [31:0] r8; assign r8 = sel[8] ? MEM[8] : mem[8];
wire [31:0] r9; assign r9 = sel[9] ? MEM[9] : mem[9];
wire [31:0] r10; assign r10 = sel[10] ? MEM[10] : mem[10];
wire [31:0] r11; assign r11 = sel[11] ? MEM[11] : mem[11];
wire [31:0] r12; assign r12 = sel[12] ? MEM[12] : mem[12];
wire [31:0] r13; assign r13 = sel[13] ? MEM[13] : mem[13];
wire [31:0] r14; assign r14 = sel[14] ? MEM[14] : mem[14];
wire [31:0] r15; assign r15 = sel[15] ? MEM[15] : mem[15];
wire [31:0] r16; assign r16 = sel[16] ? MEM[16] : mem[16];
wire [31:0] r17; assign r17 = sel[17] ? MEM[17] : mem[17];
wire [31:0] r18; assign r18 = sel[18] ? MEM[18] : mem[18];
wire [31:0] r19; assign r19 = sel[19] ? MEM[19] : mem[19];
wire [31:0] r20; assign r20 = sel[20] ? MEM[20] : mem[20];
wire [31:0] r21; assign r21 = sel[21] ? MEM[21] : mem[21];
wire [31:0] r22; assign r22 = sel[22] ? MEM[22] : mem[22];
wire [31:0] r23; assign r23 = sel[23] ? MEM[23] : mem[23];
wire [31:0] r24; assign r24 = sel[24] ? MEM[24] : mem[24];
wire [31:0] r25; assign r25 = sel[25] ? MEM[25] : mem[25];
wire [31:0] r26; assign r26 = sel[26] ? MEM[26] : mem[26];
wire [31:0] r27; assign r27 = sel[27] ? MEM[27] : mem[27];
wire [31:0] r28; assign r28 = sel[28] ? MEM[28] : mem[28];
wire [31:0] r29; assign r29 = sel[29] ? MEM[29] : mem[29];
wire [31:0] r30; assign r30 = sel[30] ? MEM[30] : mem[30];
wire [31:0] r31; assign r31 = sel[31] ? MEM[31] : mem[31];
wire [31:0] r32; assign r32 = sel[32] ? MEM[32] : mem[32];
wire [31:0] r33; assign r33 = sel[33] ? MEM[33] : mem[33];
wire [31:0] r34; assign r34 = sel[34] ? MEM[34] : mem[34];
wire [31:0] r35; assign r35 = sel[35] ? MEM[35] : mem[35];
wire [31:0] r36; assign r36 = sel[36] ? MEM[36] : mem[36];
wire [31:0] r37; assign r37 = sel[37] ? MEM[37] : mem[37];
wire [31:0] r38; assign r38 = sel[38] ? MEM[38] : mem[38];
wire [31:0] r39; assign r39 = sel[39] ? MEM[39] : mem[39];
// assertions_end
wire [31:0] r0; assign r0 = sel[0] ? MEM[0] : mem[0];
wire [31:0] r1; assign r1 = sel[1] ? MEM[1] : mem[1];
wire [31:0] r2; assign r2 = sel[2] ? MEM[2] : mem[2];
wire [31:0] r3; assign r3 = sel[3] ? MEM[3] : mem[3];
wire [31:0] r4; assign r4 = sel[4] ? MEM[4] : mem[4];
wire [31:0] r5; assign r5 = sel[5] ? MEM[5] : mem[5];
wire [31:0] r6; assign r6 = sel[6] ? MEM[6] : mem[6];
wire [31:0] r7; assign r7 = sel[7] ? MEM[7] : mem[7];
wire [31:0] r8; assign r8 = sel[8] ? MEM[8] : mem[8];
wire [31:0] r9; assign r9 = sel[9] ? MEM[9] : mem[9];
wire [31:0] r10; assign r10 = sel[10] ? MEM[10] : mem[10];
wire [31:0] r11; assign r11 = sel[11] ? MEM[11] : mem[11];
wire [31:0] r12; assign r12 = sel[12] ? MEM[12] : mem[12];
wire [31:0] r13; assign r13 = sel[13] ? MEM[13] : mem[13];
wire [31:0] r14; assign r14 = sel[14] ? MEM[14] : mem[14];
wire [31:0] r15; assign r15 = sel[15] ? MEM[15] : mem[15];
wire [31:0] r16; assign r16 = sel[16] ? MEM[16] : mem[16];
wire [31:0] r17; assign r17 = sel[17] ? MEM[17] : mem[17];
wire [31:0] r18; assign r18 = sel[18] ? MEM[18] : mem[18];
wire [31:0] r19; assign r19 = sel[19] ? MEM[19] : mem[19];
wire [31:0] r20; assign r20 = sel[20] ? MEM[20] : mem[20];
wire [31:0] r21; assign r21 = sel[21] ? MEM[21] : mem[21];
wire [31:0] r22; assign r22 = sel[22] ? MEM[22] : mem[22];
wire [31:0] r23; assign r23 = sel[23] ? MEM[23] : mem[23];
wire [31:0] r24; assign r24 = sel[24] ? MEM[24] : mem[24];
wire [31:0] r25; assign r25 = sel[25] ? MEM[25] : mem[25];
wire [31:0] r26; assign r26 = sel[26] ? MEM[26] : mem[26];
wire [31:0] r27; assign r27 = sel[27] ? MEM[27] : mem[27];
wire [31:0] r28; assign r28 = sel[28] ? MEM[28] : mem[28];
wire [31:0] r29; assign r29 = sel[29] ? MEM[29] : mem[29];
wire [31:0] r30; assign r30 = sel[30] ? MEM[30] : mem[30];
wire [31:0] r31; assign r31 = sel[31] ? MEM[31] : mem[31];
wire [31:0] r32; assign r32 = sel[32] ? MEM[32] : mem[32];
wire [31:0] r33; assign r33 = sel[33] ? MEM[33] : mem[33];
wire [31:0] r34; assign r34 = sel[34] ? MEM[34] : mem[34];
wire [31:0] r35; assign r35 = sel[35] ? MEM[35] : mem[35];
wire [31:0] r36; assign r36 = sel[36] ? MEM[36] : mem[36];
wire [31:0] r37; assign r37 = sel[37] ? MEM[37] : mem[37];
wire [31:0] r38; assign r38 = sel[38] ? MEM[38] : mem[38];
wire [31:0] r39; assign r39 = sel[39] ? MEM[39] : mem[39];
 
always @ (posedge i_clk)
begin
144,4 → 142,9
end
 
endmodule // bram_wrapper.v
 
`default_nettype wire
 
// ----------------------------------------------------------------------------
// EOF
// ----------------------------------------------------------------------------
/zap/trunk/src/rtl/cpu/zap_shift_shifter.v
100,4 → 100,9
///////////////////////////////////////////////////////////////////////////////
 
endmodule // zap_shift_shifter.v
 
`default_nettype wire
 
// ----------------------------------------------------------------------------
// EOF
// ----------------------------------------------------------------------------
/zap/trunk/src/rtl/cpu/zap_shifter_main.v
259,7 → 259,6
i_alu_operation_ff == SMLALL ||
i_alu_operation_ff == SMLALH) ?
MOV : i_alu_operation_ff;
// Multiplication becomes a MOV for ALU.
o_flag_update_ff <= i_flag_update_ff;
o_mem_srcdest_index_ff <= i_mem_srcdest_index_ff;
o_mem_load_ff <= i_mem_load_ff;
375,47 → 374,23
input result_from_alu_valid // Result from ALU is VALID.
);
begin
`ifdef SH_DEBUG
$display($time, "%m: ================ resolve_conflict ==================");
$display($time, "%m: index from issue = %d value from issue = %d index from this stage = %d result from alu = %d", index_from_issue, value_from_issue, index_from_this_stage, result_from_alu);
$display($time, "%m: ====================================================");
`endif
 
if ( index_from_issue[32] == IMMED_EN )
begin
resolve_conflict = index_from_issue[31:0];
 
`ifdef SH_DEBUG
$display($time, "%m: => It is an immediate value.");
`endif
end
else if ( index_from_issue == PHY_PC )
begin
resolve_conflict = i_pc_plus_8_ff;
 
`ifdef SH_DEBUG
$display($time, "%m: => Giving PC");
`endif
end
else if ( index_from_this_stage == index_from_issue[$clog2(PHY_REGS)-1:0] && result_from_alu_valid )
begin
resolve_conflict = result_from_alu;
 
`ifdef SH_DEBUG
$display($time, "%m: => Getting result from ALU!");
`endif
end
else
begin
resolve_conflict = value_from_issue[31:0];
`ifdef SH_DEBUG
$display($time, "%m: => No changes!");
`endif
end
 
`ifdef SH_DEBUG
$display($time, "%m: ==> Final result is %d", resolve_conflict);
`endif
end
endfunction
 
422,4 → 397,9
///////////////////////////////////////////////////////////////////////////////
 
endmodule // zap_shifter_main.v
 
`default_nettype wire
 
// ----------------------------------------------------------------------------
// EOF
// ----------------------------------------------------------------------------
/zap/trunk/src/rtl/cpu/zap_shifter_multiply.v
222,4 → 222,9
///////////////////////////////////////////////////////////////////////////////
 
endmodule // zap_multiply.v
 
`default_nettype wire
 
// ----------------------------------------------------------------------------
// EOF
// ----------------------------------------------------------------------------
/zap/trunk/src/rtl/cpu/zap_sync_fifo.v
157,3 → 157,7
endmodule // zap_sync_fifo
 
`default_nettype wire
 
// ----------------------------------------------------------------------------
// EOF
// ----------------------------------------------------------------------------
/zap/trunk/src/rtl/cpu/zap_thumb_decoder.v
27,7 → 27,6
// -- --
// -----------------------------------------------------------------------------
 
 
`default_nettype none
 
module zap_thumb_decoder (
184,3 → 183,7
endmodule // zap_thumb_decoder
 
`default_nettype wire
 
// ----------------------------------------------------------------------------
// EOF
// ----------------------------------------------------------------------------
/zap/trunk/src/rtl/cpu/zap_tlb_check.v
89,9 → 89,10
output reg o_cacheable; // Cacheble stats of the PTE.
output reg [31:0] o_phy_addr; // Physical address.
 
// ----------------------------------------------------------------------------
 
always @*
begin
 
// Default values. Taken for MMU disabled esp.
o_fsr = 0; // No fault.
o_far = i_va; // Fault address.
252,6 → 253,10
end
endfunction
 
endmodule // zap_tlb_check.v
 
endmodule // zap_tlb_check.v
`default_nettype wire
 
// ----------------------------------------------------------------------------
// EOF
// ----------------------------------------------------------------------------
/zap/trunk/src/rtl/cpu/zap_tlb_fsm.v
173,15 → 173,6
begin
if ( i_walk )
begin
$display($time, " - %m :: Page fault! Need to page walk! i_walk = %b", i_walk);
$display($time, " - %m :: Core generated address %x", i_address);
$display($time, " - %m :: Moving to FETCH_L1_DESC. i_baddr = %x baddr_tran_base = %x addr_va_table_index = %x",
i_baddr, i_baddr[`VA__TRANSLATION_BASE], i_address[`VA__TABLE_INDEX]);
 
`ifdef TLB_DEBUG
$stop;
`endif
 
o_busy = 1'd1;
 
/*
195,34 → 186,16
end
else if ( i_fsr[3:0] != 4'b0000 ) /* Access Violation. */
begin
$display($time, " - %m :: Access violation fsr = %x far = %x...", i_fsr, i_far);
 
`ifdef TLB_DEBUG
$stop;
`endif
 
o_fault = 1'd1;
o_busy = 1'd0;
o_fsr = i_fsr;
o_far = i_far;
end
else
begin
`ifdef DISP_TLB_SUCCESS
$display($time, " - %m :: TLB Hit for address = %x MMU enable = %x!", i_address, i_mmu_en);
`endif
 
`ifdef TLB_DEBUG
$stop;
`endif
end
end
end
 
FETCH_L1_DESC_0:
begin
$display($time, " - %m :: In state FETCH_L1_DESC_0");
 
o_busy = 1;
 
if ( i_wb_ack )
229,8 → 202,6
begin
dnxt = i_wb_dat;
state_nxt = FETCH_L1_DESC;
 
$display($time, " - %m :: Received %x from WB. Moving to FETCH_L1_DESC...", dnxt );
end
else tsk_hold_wb_access;
end
242,18 → 213,10
* Examine it. dff holds the L1 descriptor.
*/
 
$display($time, " - %m :: In FETCH_L1_DESC state...");
 
o_busy = 1'd1;
 
if ( 1 )
begin
$display($time, " - %m :: ACK received. Read data is %x", i_wb_dat);
 
`ifdef TLB_DEBUG
$stop;
`endif
 
case ( dff[`ID] )
 
SECTION_ID:
268,8 → 231,6
dff};
state_nxt = REFRESH_CYCLE;
 
$display($time, " - %m :: It is a section ID. Writing to section TLB as %x. Moving to refresh cycle...", o_setlb_wdata);
 
$display($time, " - %m :: #########################################################");
$display($time, " - %m :: SECTION DESCRIPTOR DETAILS #");
$display($time, " - %m :: #########################################################");
279,10 → 240,6
$display($time, " - %m :: # Cacheable = 0b%b", o_setlb_wdata[`SECTION_TLB__CB] >> 1);
$display($time, " - %m :: # Bufferable = 0b%b", o_setlb_wdata[`SECTION_TLB__CB] & 2'b01);
$display($time, " - %m :: #########################################################");
 
`ifdef TLB_DEBUG
$stop;
`endif
end
 
PAGE_ID:
298,12 → 255,6
 
tsk_prpr_wb_rd({dff[`L1_PAGE__PTBR],
i_address[`VA__L2_TABLE_INDEX], 2'd0});
 
$display($time, " - %m :: L1 received Page ID.");
 
`ifdef TLB_DEBUG
$stop;
`endif
end
 
default: /* Generate section translation fault. Fault Class II */
314,12 → 265,6
o_fault = 1'd1;
o_busy = 1'd0;
state_nxt = IDLE;
 
$display($time, " - %m :: FSR section translation fault!");
 
`ifdef TLB_DEBUG
$stop;
`endif
end
endcase
412,12 → 357,6
 
REFRESH_CYCLE:
begin
$display($time, " - %m :: Entered refresh cycle. Moving to IDLE...");
 
`ifdef TLB_DEBUG
$stop;
`endif
 
o_busy = 1'd1;
state_nxt = IDLE;
end
463,12 → 402,6
 
task tsk_prpr_wb_rd ( input [31:0] adr );
begin
$display($time, " - %m :: Reading from location %x", adr);
 
`ifdef TLB_DEBUG
$stop;
`endif
 
wb_stb_nxt = 1'd1;
wb_cyc_nxt = 1'd1;
wb_adr_nxt = adr;
476,22 → 409,10
end
endtask
 
// ----------------------------------------------------------------------------
 
// assertions_start
 
always @ (posedge i_mmu_en)
begin
$display($time, " - %m :: MMU Enabled!");
end
 
always @ (negedge i_mmu_en)
begin
$display($time, " - %m :: MMU Disabled!");
end
 
// assertions_end
 
endmodule // zap_tlb_fsm.v
 
`default_nettype wire
 
// ----------------------------------------------------------------------------
// END OF FILE
// ----------------------------------------------------------------------------
/zap/trunk/src/rtl/cpu/zap_wb_adapter.v
207,7 → 207,6
if ( I_WB_CTI == CTI_BURST ) // Burst of 4 words. Each word is 4 byte.
begin
state_nxt = PRPR_RD_BURST;
$display($time, " - %m :: Read burst requested. Base address = %x", I_WB_ADR);
end
else // Single.
begin
235,7 → 234,6
if ( O_WB_ACK )
begin
dnxt = dff + 1'd1;
$display($time, " - %m :: Early response received for read burst. Data received %x", O_WB_DAT);
end
 
if ( ctr_ff == BURST_LEN * 4 )
255,9 → 253,6
ctr_ff == 12 ? 1'd1 : 1'd0,
1'd0 };
ctr_nxt = ctr_ff + 4;
 
$display($time, " - %m :: Read Burst. Writing data SEL = %x DATA = %x ADDR = %x EOB = %x WEN = %x to the FIFO",
fsm_write_data[69:66], fsm_write_data[65:34], fsm_write_data[33:2], fsm_write_data[1], fsm_write_data[0]);
end
end
 
292,7 → 287,6
if ( O_WB_ACK )
begin
dnxt = dff + 1;
$display($time, " - %m :: Read Burst. ACK sent. Data provided is %x", O_WB_DAT);
end
 
if ( dff == BURST_LEN && !o_wb_stb )
305,4 → 299,9
end
 
endmodule
 
`default_nettype wire
 
// ----------------------------------------------------------------------------
// EOF
// ----------------------------------------------------------------------------
/zap/trunk/src/rtl/cpu/zap_wb_merger.v
31,6 → 31,7
 
module zap_wb_merger (
 
// Clock and reset
input wire i_clk,
input wire i_reset,
 
156,4 → 157,9
end
 
endmodule
 
`default_nettype wire
 
// ----------------------------------------------------------------------------
// EOF
// ----------------------------------------------------------------------------
/zap/trunk/src/rtl/cpu/zap_writeback.v
119,9 → 119,9
`include "zap_localparams.vh"
`include "zap_functions.vh"
 
// ----------------------------------------------
// ----------------------------------------------------------------------------
// Localparams
// ----------------------------------------------
// ----------------------------------------------------------------------------
 
`ifndef ARM_MODE
`define ARM_MODE (cpsr_ff[T] == 1'd0)
135,22 → 135,10
localparam IRQ_VECTOR = 32'h00000018;
localparam FIQ_VECTOR = 32'h0000001C;
 
// ----------------------------------------------
// ----------------------------------------------------------------------------
// Variables
// ----------------------------------------------
// ----------------------------------------------------------------------------
 
// assertions_start
reg fiq_ack;
reg irq_ack;
reg und_ack;
reg dabt_ack;
reg iabt_ack;
reg swi_ack;
integer irq_addr = 0;
reg temp_set = 0;
reg error = 0;
// assertions_end
 
reg [31:0] cpsr_ff, cpsr_nxt;
reg [31:0] pc_ff, pc_nxt;
reg [$clog2(PHY_REGS)-1:0] wa1, wa2;
164,9 → 152,9
assign o_pc_nxt = pc_nxt & 32'hfffffffe;
assign o_cpsr_nxt = cpsr_nxt;
 
// ----------------------------------------------
// ----------------------------------------------------------------------------
// Register file
// ----------------------------------------------
// ----------------------------------------------------------------------------
 
zap_register_file u_zap_register_file
(
192,9 → 180,9
.o_rd_data_d ( o_rd_data_3 )
);
 
// ---------------------------------------------
// ----------------------------------------------------------------------------
// Combinational Logic
// ---------------------------------------------
// ----------------------------------------------------------------------------
 
always @ (*)
begin: blk1
204,15 → 192,6
shelve_nxt = shelve_ff;
pc_shelve_nxt = pc_shelve_ff;
 
// assertions_start
fiq_ack = 0;
irq_ack = 0;
und_ack = 0;
dabt_ack = 0;
iabt_ack = 0;
swi_ack = 0;
// assertions_end
 
o_hijack = 0;
o_hijack_op1 = 0;
o_hijack_op2 = 0;
291,16 → 270,9
wa2 = PHY_ABT_SPSR;
wdata2 = cpsr_ff;
cpsr_nxt[`CPSR_MODE] = ABT;
 
// assertions_start
dabt_ack = 1'd1;
// assertions_end
 
end
else if ( i_fiq )
begin
$display($time, " - %m :: FIQ detected.");
 
// Returns do LR - 4 to get back to the same instruction.
pc_shelve ( FIQ_VECTOR );
 
311,15 → 283,9
wdata2 = cpsr_ff;
cpsr_nxt[`CPSR_MODE] = FIQ;
cpsr_nxt[F] = 1'd1;
 
// assertions_start
fiq_ack = 1'd1;
// assertions_end
end
else if ( i_irq )
begin
$display($time, " - %m :: IRQ detected.");
 
pc_shelve (IRQ_VECTOR);
 
wen = 1;
329,11 → 295,6
wdata2 = cpsr_ff;
cpsr_nxt[`CPSR_MODE] = IRQ;
// Returns do LR - 4 to get back to the same instruction.
 
// assertions_start
irq_addr = wdata1;
irq_ack = 1'd1;
// assertions_end
end
else if ( i_instr_abt )
begin
346,10 → 307,6
wa2 = PHY_ABT_SPSR;
wdata2 = cpsr_ff;
cpsr_nxt[`CPSR_MODE] = ABT;
 
// assertions_start
iabt_ack = 1'd1;
// assertions_end
end
else if ( i_swi )
begin
362,10 → 319,6
wa2 = PHY_SVC_SPSR;
wdata2 = cpsr_ff;
cpsr_nxt[`CPSR_MODE] = SVC;
 
// assertions_start
swi_ack = 1'd1;
// assertions_end
end
else if ( i_und )
begin
378,10 → 331,6
wa2 = PHY_UND_SPSR;
wdata2 = cpsr_ff;
cpsr_nxt[`CPSR_MODE] = UND;
 
// assertions_start
und_ack = 1'd1;
// assertions_end
end
else if ( i_copro_reg_en )
begin
409,8 → 358,6
// Load to PC will trigger from writeback.
if ( i_mem_load_ff && i_wr_index_1 == ARCH_PC)
begin
$display($time, " - %m :: Detected load to PC. Trigger a writeback.");
 
pc_shelve (i_wr_data_1);
o_clear_from_writeback = 1'd1;
end
420,9 → 367,9
pc_nxt = pc_nxt & 32'hffff_fffe;
end
 
// ----------------------------------------------
// ----------------------------------------------------------------------------
// Sequential Logic
// ----------------------------------------------
// ----------------------------------------------------------------------------
 
always @ ( posedge i_clk )
begin
448,9 → 395,9
end
end
 
// ----------------------------------------------
// ----------------------------------------------------------------------------
// Tasks
// ----------------------------------------------
// ----------------------------------------------------------------------------
 
task pc_shelve (input [31:0] new_pc);
begin
468,30 → 415,31
end
endtask
 
// assertions_start
 
always @ (*)
if ( cpsr_nxt[`CPSR_MODE] != USR && cpsr_ff[`CPSR_MODE] == USR )
always @ (*)
if ( cpsr_nxt[`CPSR_MODE] != USR && cpsr_ff[`CPSR_MODE] == USR )
begin
if (
i_data_abt ||
i_fiq ||
i_irq ||
i_instr_abt ||
i_swi ||
i_und
)
begin
if (
i_data_abt ||
i_fiq ||
i_irq ||
i_instr_abt ||
i_swi ||
i_und
)
begin
// OKAY...
end
else
begin
$display($time, "Error : %m CPU is changing out of USR mode without an exception...");
$stop;
end
// OKAY...
end
else
begin
$display($time, "Error : %m CPU is changing out of USR mode without an exception...");
$stop;
end
end
 
// assertions_end
endmodule // zap_register_file.v
 
endmodule // zap_register_file.v
`default_nettype wire
 
// ----------------------------------------------------------------------------
// END OF FILE
// ----------------------------------------------------------------------------
/zap/trunk/src/ts/makefile
0,0 → 1,6
default:
xterm -hold -e 'cd arm_test ; make' &
xterm -hold -e 'cd thumb_test ; make' &
xterm -hold -e 'cd factorial ; make' &
xterm -hold -e 'cd uart ; make' &
 
/zap/trunk/README.md
10,6 → 10,8
 
This project was created for the ORCONF-2016 Student Design Contest.
 
ZAP is specifically designed to work with FPGAs.
 
![Wishbone logo](https://wishbone-interconnect.readthedocs.io/en/latest/_images/wishbone_stamp.svg)
 
#### Repos
46,8 → 48,10
|CP15 Compliance | v5T (No fine pages) |
|FCSE Support | Yes |
 
* 10-stage pipeline design. Pipeline has bypass network to resolve dependencies. Most operations execute at a rate of 1 operation per clock.
* 10-stage pipeline design. Pipeline has extensive bypass network to resolve dependencies. Most operations execute at a rate of 1 operation per clock.
* 2 write ports for the register file to allow LDR/STR with writeback to execute as a single instruction.
* Instructions of ALU + Shift can allow execution of subsequent commands with dependencies if the subsequent command doesn't use the shifter. This is done by having a dual feedback network.
* The core is specifically designed for use in FGPA and relies on FGPA inference to allow portability across FPGA vendors.
 
#### CPU Configuration (zap_top.v)
 
90,11 → 94,10
| output | [31:0] | o_wb_adr_nxt | IGNORE THIS PORT. LEAVE OPEN. |
 
 
### Getting Started
### Run Sample Tests
 
*Tested on Ubuntu 16.04 LTS/18.04 LTS*
 
#### Run Sample Tests
 
Let the variable $test_name hold the name of the test. See the src/ts directory for some basic tests pre-installed. Available test names are: factorial, arm_test, thumb_test, uart. New tests can be added using these as starting templates. Please note that these will be run on the SOC platform (chip_top) that consist of the ZAP processor, 2 x UARTs, a VIC and a timer.
 
```bash
107,104 → 110,12
```
To use this processor in your SOC, instantiate this top level CPU module in your project: /src/rtl/cpu/zap_top.v
 
### Implementation Specific Details
### FPGA Timing Performance (Vivado, Retime Enabled)
 
#### FPGA Timing Performance (Vivado, Retime Enabled)
 
| FPGA Part | Speed | Critical Path |
|--------------------|-------|----------------|
| xc7a35tiftg256-1L | 80MHz | Cache access |
 
#### Coprocessor #15 Control Registers
 
##### Register 0 : ID Register
 
|Bits | Name | Description |
|-----|---------|------------------------------------------|
|31:0 | Various | Processor ID info. |
 
##### Register 1 : Control
 
|Bits | Name | Description |
|-----|-----------|------------------------------------------|
|0 | M | MMU Enable. Active high |
|1 | A | Always 0. Alignment check off |
|2 | D | Data Cache Enable. Active high |
|3 | W | Always 1. Write Buffer always on. |
|4 | P | Always 1. RESERVED |
|5 | D | Always 1. RESERVED |
|6 | L | Always 1. RESERVED |
|7 | B | Always 0. Little Endian |
|8 | S | The S bit |
|9 | R | The R bit |
|11 | Z | Always 1. Branch prediction enabled |
|12 | I | Instruction Cache Enable. Active high |
|13 | V | Normal Exception Vectors. Always 0 |
|14 | RR | Always 1. Direct mapped cache. |
|15 | L4 | Always 0. Normal behavior. |
 
##### Register 2 : Translation Base Address
 
|Bits | Name | Description |
|-----|-----------|------------------------------------------|
|13:0 | M | Preserve value. |
|31:14| TTB | Upper 18-bits of translation address |
 
##### Register 3 : Domain Access Control (X=0 to X=15)
 
|Bits | Name | Description |
|---------|-----------|------------------------------------------|
|2X+1:2X | DX | DX access permission. |
 
##### Register 5 : Fault Status Register
 
|Bits | Name | Description |
|-----|-----------|------------------------------------------|
|3:0 | Status | Status. |
|1:0 | Domain | Domain. |
|11:8 | SBZ | Always 0. RESERVED |
 
##### Register 6 : Fault Address Register
 
|Bits | Name | Description |
|-----|-----------|------------------------------------------|
|31:0 | Addr | Fault Address. |
 
##### Register 7 : Cache Functions
 
| Opcode2 | CRm | Description |
|-------------|-----------------|-------------------------------------|
| 000 | 0111 | Flush all caches. |
| 000 | 0101 | Flush I cache. |
| 000 | 0110 | Flush D cache. |
| 000 | 1011 | Clean all caches. |
| 000 | 1010 | Clean D cache. |
| 000 | 1111 | Clean and flush all caches. |
| 000 | 1110 | Clean and flush D cache. |
| Other | Other | Clean and flush ALL caches |
 
 
##### Register 8 : TLB Functions
 
|Opcode2 | CRm | Description |
|--------|---------------|-------------------------|
| 000 | 0111 | Flush all TLBs |
| 000 | 0101 | Flush I TLB |
| 000 | 0110 | Flush D TLB |
| Other| Other | Flush all TLBs |
 
##### Register 13 : FCSE Extentions
 
| Field | Description |
|-------|-------------|
| 31:25 | PID |
 
##### Lockdown Support
* CPU memory system does not support lockdown.
 
##### Tiny Pages
* No support for tiny pages (1KB).
 
### License
 
 

powered by: WebSVN 2.1.0

© copyright 1999-2024 OpenCores.org, equivalent to Oliscience, all rights reserved. OpenCores®, registered trademark.