Commit b25e4d38 authored by Tomasz Wlostowski's avatar Tomasz Wlostowski

wip

parent 7dc634dc
......@@ -22,6 +22,33 @@
`timescale 1ns/1ps
module chipscope_icon(
CONTROL0) /* synthesis syn_black_box syn_noprune=1 */;
inout [35 : 0] CONTROL0;
endmodule
module chipscope_ila(
CONTROL,
CLK,
TRIG0,
TRIG1,
TRIG2,
TRIG3) /* synthesis syn_black_box syn_noprune=1 */;
inout [35 : 0] CONTROL;
input CLK;
input [31 : 0] TRIG0;
input [31 : 0] TRIG1;
input [31 : 0] TRIG2;
input [31 : 0] TRIG3;
endmodule
module rv_cpu
(
input clk_i,
......@@ -60,7 +87,6 @@ module rv_cpu
wire f2d_valid;
wire f_stall_req;
wire d2x_valid;
......@@ -110,6 +136,39 @@ module rv_cpu
.x_bra_i(x2f_bra)
);
wire [35:0] CONTROL;
wire [31:0] TRIG0, TRIG1, TRIG2, TRIG3;
wire x_load_comb;
wire x2w_load_hazard;
wire w_stall_req;
wire x_stall_req;
chipscope_icon icon0(
.CONTROL0( CONTROL) );
chipscope_ila ila0(
.CONTROL(CONTROL),
.CLK(clk_i),
.TRIG0(TRIG0),
.TRIG1(TRIG1),
.TRIG2(TRIG2),
.TRIG3(TRIG3) );
assign TRIG0 = f2d_pc;
assign TRIG1 = f2d_ir;
assign TRIG2[0] = rst_i;
assign TRIG2[1] = f2d_valid;
assign TRIG2[2] = f_kill;
assign TRIG2[3] = f_stall;
assign TRIG2[4] = w_stall_req;
assign TRIG2[5] = x_stall_req;
rv_decode decode
(
......@@ -204,11 +263,6 @@ module rv_cpu
);
wire x_load_comb;
wire x2w_load_hazard;
wire w_stall_req;
......@@ -279,6 +333,7 @@ module rv_cpu
);
wire [31:0] wb_trig2;
rv_writeback writeback
......@@ -306,9 +361,27 @@ module rv_cpu
.rf_rd_value_o(rf_rd_value),
.rf_rd_o(rf_rd),
.rf_rd_write_o(rf_rd_write)
.rf_rd_write_o(rf_rd_write),
.TRIG2(wb_trig2)
);
assign TRIG2[15:6] = wb_trig2[15:6];
assign TRIG3 = dm_addr_o;
reg [5:0] stall_timeout;
always@(posedge clk_i)
if(!w_stall_req)
stall_timeout <= 0;
else if(stall_timeout != 63)
stall_timeout <= stall_timeout + 1;
assign TRIG2[16] = (stall_timeout == 63) ? 1'b1 : 1'b0;
rv_timer ctimer (
.clk_i(clk_i),
......
......@@ -55,7 +55,7 @@ module rv_csr
);
reg [31:0] csr_mscratch = 0;
reg [31:0] csr_mscratch;
reg [31:0] csr_in1;
reg [31:0] csr_in2;
......
......@@ -379,9 +379,14 @@ module rv_exec
wire is_load = (d_opcode_i == `OPC_LOAD ? 1: 0) && d_valid_i && !x_kill_i;
wire is_store = (d_opcode_i == `OPC_STORE ? 1: 0) && d_valid_i && !x_kill_i;
assign dm_load_o = is_load;
assign dm_store_o = is_store;
assign dm_load_o = is_load && !x_stall_i;
assign dm_store_o = is_store && !x_stall_i;
wire trig_ent = (d_pc_i == 'h264 && !x_kill_i);
wire trig_ret = (d_pc_i == 'h2bc && !x_kill_i);
wire trig_wr = (dm_addr == 'hf368 && is_store && !x_stall_i);
always@(posedge clk_i)
if (rst_i) begin
......
......@@ -179,7 +179,7 @@ module rv_decode
x_is_signed_compare_o <= ( ( d_opcode == `OPC_BRANCH) && ( ( d_fun == `BRA_GE )|| (d_fun == `BRA_LT ) ) )
|| ( ( (d_opcode == `OPC_OP) || (d_opcode == `OPC_OP_IMM) ) && (d_fun == `FUNC_SLT ) );
x_is_add_o <= !((d_opcode == `OPC_OP && d_fun == `FUNC_ADD && f_ir_i[30]) || (d_fun == `FUNC_SLT) || (d_fun == `FUNC_SLTU));
x_is_add_o <= (d_opcode == `OPC_JAL) || (!((d_opcode == `OPC_OP && d_fun == `FUNC_ADD && f_ir_i[30]) || (d_fun == `FUNC_SLT) || (d_fun == `FUNC_SLTU)));
x_is_signed_alu_op_o <= (d_fun == `FUNC_SLT);
......
......@@ -47,7 +47,9 @@ module rv_writeback
output [31:0] rf_rd_value_o,
output [4:0] rf_rd_o,
output rf_rd_write_o
output rf_rd_write_o,
output [31:0] TRIG2
);
reg [31:0] load_value;
......@@ -97,10 +99,14 @@ module rv_writeback
end // always@ *
reg pending_load = 0, pending_store = 0, pending_load_hazard = 0;
reg pending_load, pending_store, pending_load_hazard ;
always@(posedge clk_i)
begin
if(rst_i) begin
pending_load <= 0;
pending_store <= 0;
pending_load_hazard <= 0;
end else begin
if(x_load_i && !dm_load_done_i) begin
pending_load <= 1;
pending_load_hazard <= x_load_hazard_i;
......@@ -117,11 +123,13 @@ module rv_writeback
end
reg interlock_d = 0;
reg interlock_d ;
wire interlock = ( ( x_load_i || pending_load ) && dm_load_done_i && (x_load_hazard_i || pending_load_hazard ) );
always@(posedge clk_i)
begin
if (rst_i) begin
interlock_d <= 0;
end else begin
if(interlock_d)
interlock_d <= 0;
else
......@@ -136,5 +144,15 @@ module rv_writeback
assign w_stall_req_o = ((x_load_i || pending_load) && !dm_load_done_i) || ((x_store_i || pending_store) && !dm_store_done_i) || (interlock && !interlock_d);
assign TRIG2[6] = x_load_i;
assign TRIG2[7] = pending_load;
assign TRIG2[8] = dm_load_done_i;
assign TRIG2[9] = x_store_i;
assign TRIG2[10] = pending_store;
assign TRIG2[11] = dm_store_done_i;
assign TRIG2[12] = interlock;
assign TRIG2[13] = interlock_d;
assign TRIG2[14] = pending_load_hazard;
assign TRIG2[15] = w_stall_req_o;
endmodule // rv_writeback
......@@ -31,7 +31,8 @@
#define BASE_UART 0x20000
#define BASE_GPIO 0x21000
#define UART_BAUDRATE 115200
//#define UART_BAUDRATE 115200
#define UART_BAUDRATE 10000000
static inline void writel ( uint32_t reg, uint32_t val)
{
......
......@@ -15,9 +15,12 @@ _exception_handler:
_entry:
nop
nop
la gp, _gp # Initialize global pointer
la gp, _gp # Initialize global pointer
la sp, _fstack
la t0, _fexception_stack
csrrw t0, mscratch, t0
......
......@@ -8,7 +8,7 @@ OBJCOPY = $(CROSS_COMPILE)objcopy
SIZE = $(CROSS_COMPILE)size
CFLAGS = -g -m32 -msoft-float -march=RV32I -I. -I../common
OBJS = ../common/crt0.o ../common/irq.o main.o ../common/uart.o
OBJS = ../common/crtuser.o main.o ../common/uart.o ../common/printf.o ../common/vsprintf-xint.o
LDS = ../common/ram2.ld
OUTPUT=hello
......@@ -16,7 +16,8 @@ $(OUTPUT): $(LDS) $(OBJS)
${CC} -g -m32 -msoft-float -march=RV32I -o $(OUTPUT).elf -nostartfiles $(OBJS) -lm -L../coremark -lcoremark -T $(LDS)
${OBJCOPY} -O binary $(OUTPUT).elf $(OUTPUT).bin
${OBJDUMP} -D $(OUTPUT).elf > disasm.S
# ../genraminit $(OUTPUT).bin 1024 0 0 > uart-bootloader.ram
../genraminit $(OUTPUT).bin 16384 > $(OUTPUT).ram
$(SIZE) $(OUTPUT).elf
clean:
......
......@@ -4,6 +4,13 @@
#define GPIO_CODR 0x0
#define GPIO_SODR 0x4
#define read_csr(reg) ({ unsigned long __tmp; \
asm volatile ("csrr %0, " #reg : "=r"(__tmp)); \
__tmp; })
#define write_csr(reg, val) \
asm volatile ("csrw " #reg ", %0" :: "r"(val))
void gpio_set(int pin, int value)
{
if(value)
......@@ -24,6 +31,18 @@ volatile int irq_count = 0;
void handle_trap()
{
irq_count++;
asm volatile ("li t0, 0x200\ncsrc mip, t0");
}
void enable_irqs()
{
asm volatile ("li t0, 0x200\ncsrs mie, t0");
asm volatile ("csrs mstatus, 0x1");
}
uint32_t sys_get_ticks()
{
return read_csr(0xc01);
}
extern void coremark_main();
......@@ -31,15 +50,18 @@ main()
{
uart_init_hw();
// coremark_main();
pp_printf("Hello, world [%d]!\n\r", sys_get_ticks());
coremark_main();
// for(;;);
enable_irqs();
for(;;)
{
// volatile int t = rdtime();
// puts("Hello, world!\n\r");
pp_printf("Hello, world [%d]!\n\r", sys_get_ticks());
gpio_set(0, 1);
gpio_set(1, 1);
gpio_set(2, 1);
......
......@@ -3,19 +3,30 @@
.global _start
_start:
la x1, 1234
j lab2
sll x1, x1, 1
nop
addi x1,x1,1
lab2:
la a5, lab1
lw a5, 0(a5)
lw a5, 0(a5)
lw a5, 0(a5)
nop
nop
nop
forever:
j forever
lab1:
.word lab2
lab2:
.word lab3
lab3:
.word 0xdeadbeef
/* sw x5,-16(x1)
......@@ -51,22 +62,3 @@ pass1:
sw t0,-8(sp)
*/
nop
nop
forever:
j forever
/*
# clear the bss segment
# la t0, _fbss
# la t1, _end
#1:
##ifdef __riscv64
# sd zero,0(t0)
# addi t0, t0, 8
#else
# sw zero,0(t0)
# addi t0, t0, 4
#endif
# bltu t0, t1, 1b
# call main*/
\ No newline at end of file
......@@ -62,3 +62,10 @@ while(ser.read(1) != 'G'):
time.sleep(100e-6)
print("Programming done!")
while True:
b=ser.read(1)
if(b):
sys.stdout.write(b)
else:
time.sleep(0.01)
......@@ -8,7 +8,7 @@ OBJCOPY = $(CROSS_COMPILE)objcopy
SIZE = $(CROSS_COMPILE)size
CFLAGS = -g -m32 -msoft-float -march=RV32I -O2 -I. -I../common
OBJS = ../common/crt0.o boot.o ../common/uart.o
OBJS = crt0.o irq.o boot.o ../common/uart.o
LDS = boot.ld
OUTPUT=uart-bootloader
......@@ -17,8 +17,8 @@ $(OUTPUT): $(LDS) $(OBJS)
${OBJCOPY} -O binary $(OUTPUT).elf $(OUTPUT).bin
${OBJDUMP} -D $(OUTPUT).elf > disasm.S
$(SIZE) $(OUTPUT).elf
../genraminit $(OUTPUT).bin 32 0 0 > uart-bootloader.ram
../genraminit $(OUTPUT).bin 512 63488 15872 >> uart-bootloader.ram
../genraminit $(OUTPUT).bin 512 0 0 > uart-bootloader.ram
# ../genraminit $(OUTPUT).bin 512 63488 15872 >> uart-bootloader.ram
clean:
rm -f $(OUTPUT).elf $(OUTPUT).bin $(OBJS)
......
......@@ -9,7 +9,7 @@
#include "board.h"
#include "uart.h"
#define USER_START 0x0
#define USER_START 0x800
const char hexchars[] = "0123456789abcdef";
......@@ -24,11 +24,6 @@ uart_write_byte('\n');
uart_write_byte('\r');
}
void trap_entry()
{
}
int read_blocking(uint8_t *what)
{
int cnt = 500000;
......
......@@ -13,7 +13,6 @@ SECTIONS
.boot : { *(.boot) }
. = 0x0000f800;
_ftext = .;
PROVIDE( eprol = . );
......@@ -134,8 +133,6 @@ SECTIONS
PROVIDE( end = . );
_end = ALIGN(8);
PROVIDE( _fstack = 0xfffc - 0x200 );
PROVIDE( _fstack = 0xfffc - 0x400 );
PROVIDE( _fexception_stack = 0xfffc );
}
......@@ -201,7 +201,7 @@
<property xil_pn:name="Output Extended Identifiers" xil_pn:value="false" xil_pn:valueState="default"/>
<property xil_pn:name="Output File Name" xil_pn:value="spec_top" xil_pn:valueState="default"/>
<property xil_pn:name="Overwrite Compiled Libraries" xil_pn:value="false" xil_pn:valueState="default"/>
<property xil_pn:name="Pack I/O Registers into IOBs" xil_pn:value="Auto" xil_pn:valueState="default"/>
<property xil_pn:name="Pack I/O Registers into IOBs" xil_pn:value="Yes" xil_pn:valueState="non-default"/>
<property xil_pn:name="Pack I/O Registers/Latches into IOBs" xil_pn:value="Off" xil_pn:valueState="default"/>
<property xil_pn:name="Package" xil_pn:value="fgg484" xil_pn:valueState="default"/>
<property xil_pn:name="Perform Advanced Analysis" xil_pn:value="false" xil_pn:valueState="default"/>
......@@ -231,7 +231,7 @@
<property xil_pn:name="Read Cores" xil_pn:value="true" xil_pn:valueState="default"/>
<property xil_pn:name="Reduce Control Sets" xil_pn:value="Auto" xil_pn:valueState="default"/>
<property xil_pn:name="Regenerate Core" xil_pn:value="Under Current Project Setting" xil_pn:valueState="default"/>
<property xil_pn:name="Register Balancing" xil_pn:value="No" xil_pn:valueState="default"/>
<property xil_pn:name="Register Balancing" xil_pn:value="Yes" xil_pn:valueState="non-default"/>
<property xil_pn:name="Register Duplication Map" xil_pn:value="On" xil_pn:valueState="non-default"/>
<property xil_pn:name="Register Duplication Xst" xil_pn:value="true" xil_pn:valueState="default"/>
<property xil_pn:name="Register Ordering spartan6" xil_pn:value="4" xil_pn:valueState="default"/>
......@@ -355,7 +355,7 @@
<association xil_pn:name="Implementation" xil_pn:seqID="0"/>
</file>
<file xil_pn:name="../../ip_cores/general-cores/modules/wishbone/wb_uart/xwb_simple_uart.vhd" xil_pn:type="FILE_VHDL">
<association xil_pn:name="Implementation" xil_pn:seqID="31"/>
<association xil_pn:name="Implementation" xil_pn:seqID="33"/>
</file>
<file xil_pn:name="../../ip_cores/general-cores/platform/xilinx/wb_xilinx_fpga_loader/xloader_registers_pkg.vhd" xil_pn:type="FILE_VHDL">
<association xil_pn:name="Implementation" xil_pn:seqID="0"/>
......@@ -427,13 +427,13 @@
<association xil_pn:name="Implementation" xil_pn:seqID="0"/>
</file>
<file xil_pn:name="../../top/spec/spec_top.vhd" xil_pn:type="FILE_VHDL">
<association xil_pn:name="Implementation" xil_pn:seqID="34"/>
<association xil_pn:name="Implementation" xil_pn:seqID="36"/>
</file>
<file xil_pn:name="../../ip_cores/general-cores/modules/wishbone/wb_slave_adapter/wb_slave_adapter.vhd" xil_pn:type="FILE_VHDL">
<association xil_pn:name="Implementation" xil_pn:seqID="22"/>
</file>
<file xil_pn:name="../../ip_cores/general-cores/modules/wishbone/wb_gpio_port/xwb_gpio_port.vhd" xil_pn:type="FILE_VHDL">
<association xil_pn:name="Implementation" xil_pn:seqID="32"/>
<association xil_pn:name="Implementation" xil_pn:seqID="34"/>
</file>
<file xil_pn:name="../../ip_cores/general-cores/platform/xilinx/wb_xil_multiboot/multiboot_regs.vhd" xil_pn:type="FILE_VHDL">
<association xil_pn:name="Implementation" xil_pn:seqID="0"/>
......@@ -583,7 +583,7 @@
<association xil_pn:name="Implementation" xil_pn:seqID="0"/>
</file>
<file xil_pn:name="../../ip_cores/general-cores/modules/wishbone/wb_uart/wb_simple_uart.vhd" xil_pn:type="FILE_VHDL">
<association xil_pn:name="Implementation" xil_pn:seqID="27"/>
<association xil_pn:name="Implementation" xil_pn:seqID="29"/>
</file>
<file xil_pn:name="../../ip_cores/general-cores/modules/common/gc_word_packer.vhd" xil_pn:type="FILE_VHDL">
<association xil_pn:name="Implementation" xil_pn:seqID="0"/>
......@@ -598,7 +598,7 @@
<association xil_pn:name="Implementation" xil_pn:seqID="0"/>
</file>
<file xil_pn:name="../../ip_cores/general-cores/modules/wishbone/wb_gpio_port/wb_gpio_port.vhd" xil_pn:type="FILE_VHDL">
<association xil_pn:name="Implementation" xil_pn:seqID="28"/>
<association xil_pn:name="Implementation" xil_pn:seqID="30"/>
</file>
<file xil_pn:name="../../ip_cores/general-cores/modules/wishbone/wb_spi/spi_clgen.v" xil_pn:type="FILE_VERILOG">
<association xil_pn:name="Implementation" xil_pn:seqID="0"/>
......@@ -616,7 +616,7 @@
<association xil_pn:name="Implementation" xil_pn:seqID="0"/>
</file>
<file xil_pn:name="../../rtl/rv_cpu.v" xil_pn:type="FILE_VERILOG">
<association xil_pn:name="Implementation" xil_pn:seqID="26"/>
<association xil_pn:name="Implementation" xil_pn:seqID="28"/>
</file>
<file xil_pn:name="../../ip_cores/general-cores/modules/wishbone/wb_onewire_master/sockit_owm.v" xil_pn:type="FILE_VERILOG">
<association xil_pn:name="Implementation" xil_pn:seqID="0"/>
......@@ -664,13 +664,13 @@
<association xil_pn:name="Implementation" xil_pn:seqID="0"/>
</file>
<file xil_pn:name="../../ip_cores/general-cores/modules/wishbone/wb_crossbar/xwb_crossbar.vhd" xil_pn:type="FILE_VHDL">
<association xil_pn:name="Implementation" xil_pn:seqID="33"/>
<association xil_pn:name="Implementation" xil_pn:seqID="35"/>
</file>
<file xil_pn:name="../../top/spec/reset_gen.vhd" xil_pn:type="FILE_VHDL">
<association xil_pn:name="Implementation" xil_pn:seqID="29"/>
<association xil_pn:name="Implementation" xil_pn:seqID="31"/>
</file>
<file xil_pn:name="../../rtl/xrv_core.vhd" xil_pn:type="FILE_VHDL">
<association xil_pn:name="Implementation" xil_pn:seqID="30"/>
<association xil_pn:name="Implementation" xil_pn:seqID="32"/>
</file>
<file xil_pn:name="../../ip_cores/general-cores/modules/wishbone/wb_irq/wb_irq_slave.vhd" xil_pn:type="FILE_VHDL">
<association xil_pn:name="Implementation" xil_pn:seqID="0"/>
......@@ -738,6 +738,12 @@
<association xil_pn:name="BehavioralSimulation" xil_pn:seqID="178"/>
<association xil_pn:name="Implementation" xil_pn:seqID="13"/>
</file>
<file xil_pn:name="../../ip_cores/chipscope/chipscope_icon.ngc" xil_pn:type="FILE_NGC">
<association xil_pn:name="Implementation" xil_pn:seqID="27"/>
</file>
<file xil_pn:name="../../ip_cores/chipscope/chipscope_ila.ngc" xil_pn:type="FILE_NGC">
<association xil_pn:name="Implementation" xil_pn:seqID="26"/>
</file>
</files>
<bindings>
......
......@@ -156,8 +156,9 @@ module main;
initial begin
// load_ram("../../sw/test_csr/test_csr.ram");
// load_ram("../../sw/uart_bootloader/uart-bootloader.ram");
load_ram("../../sw/test2/test2.ram");
repeat(3) @(posedge clk);
rst = 0;
......
......@@ -47,6 +47,7 @@ entity spec_top is
uart_txd_o : out std_logic;
uart_rxd_i : in std_logic;
leds_o: out std_logic_vector(3 downto 0)
);
......@@ -227,7 +228,7 @@ begin -- rtl
gpio_in_i => gpio_in,
gpio_oen_o => gpio_oen);
leds_o <= gpio_out(3 downto 0);
leds_o <= gpio_out(3 downto 0);
end rtl;
Markdown is supported
0% or
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment