Digital core and ring macros harden properly.
Correctly supports multiple clock domains.
diff --git a/envsetup b/envsetup
new file mode 100644
index 0000000..077ea1d
--- /dev/null
+++ b/envsetup
@@ -0,0 +1,9 @@
+
+# For openlane.
+export CARAVEL_ROOT=$(pwd)/caravel
+export OPENLANE_ROOT=/home/harrison/workspace/OpenLane/
+export PDK_ROOT=/home/harrison/workspace/sky130/
+
+# For sim.
+export GCC_PATH=/opt/riscv32imc/bin/
+export PDK_PATH=/home/harrison/workspace/sky130/sky130A/
diff --git a/ip/randsack/rtl/collapsering_macro.v b/ip/randsack/rtl/collapsering_macro.v
index 6da1ce4..fd17492 100644
--- a/ip/randsack/rtl/collapsering_macro.v
+++ b/ip/randsack/rtl/collapsering_macro.v
@@ -29,6 +29,7 @@
output clk_out
);
+`ifndef SIM
collapsering ring (
.CLKBUFOUT(clk_out),
.START(start),
@@ -36,5 +37,27 @@
.TRIMB(trim_b),
.CLKMUX(clkmux)
);
+`else
+ // TODO(hdpham): Improve this model.
+ reg [31:0] clk_cnt;
+ reg fake_clk;
+
+ initial begin
+ clk_cnt <= 0;
+ fake_clk <= 1'b0;
+ end
+
+ always @(posedge fake_clk) begin
+ if (start == 1'b1) begin
+ clk_cnt <= clk_cnt + 32'b1;
+ end else begin
+ clk_cnt <= 32'b0;
+ end
+ end
+
+ always #5 fake_clk <= ~fake_clk;
+
+ assign clk_out = fake_clk & start & (clk_cnt < 100);
+`endif
endmodule // module collapsering_macro
diff --git a/ip/randsack/rtl/dtop.v b/ip/randsack/rtl/digitalcore_macro.v
similarity index 88%
rename from ip/randsack/rtl/dtop.v
rename to ip/randsack/rtl/digitalcore_macro.v
index 86e4b5b..9c41fb7 100644
--- a/ip/randsack/rtl/dtop.v
+++ b/ip/randsack/rtl/digitalcore_macro.v
@@ -15,7 +15,7 @@
// See the License for the specific language governing permissions and
// limitations under the License.
-module dtop (
+module digitalcore_macro (
`ifdef USE_POWER_PINS
inout vccd1,
inout vssd1,
@@ -44,7 +44,14 @@
output [`MPRJ_IO_PADS-1:0] io_oeb,
// IRQ
- output [2:0] irq
+ output [2:0] irq,
+
+ // ring0 collapsering macro
+ input ring0_clk,
+ output ring0_start,
+ output [27:0] ring0_trim_a,
+ output [27:0] ring0_trim_b,
+ output [2:0] ring0_clkmux
);
// Filter wishbone accesses from Caravel.
@@ -117,7 +124,7 @@
.wbs2_rty_i(1'b0),
.wbs2_cyc_o(ring0_cyc_i),
.wbs2_addr(RING0_BASE_ADDR),
- .wbs2_addr_msk(RING0_ADDR_MASK),
+ .wbs2_addr_msk(RING0_ADDR_MASK)
);
// GPIO signals.
@@ -167,7 +174,7 @@
wire uart_tx;
wire uart_rx;
- simpleuart_wb #(
+ simpleuart_div16_wb #(
.BASE_ADR(UART0_BASE_ADDR)
) uart0 (
.wb_clk_i(wb_clk_i),
@@ -198,12 +205,6 @@
wire ring0_ack_o;
wire [31:0] ring0_dat_o;
- wire ring0_clk;
- wire ring0_start;
- wire [27:0] ring0_trim_a;
- wire [27:0] ring0_trim_b;
- wire [2:0] ring0_clkmux;
-
ring_control #(
.CLKMUX_BITS(3),
.TRIM_BITS(28)
@@ -211,15 +212,15 @@
.wb_clk_i(wb_clk_i),
.wb_rst_i(wb_rst_i),
- .wbs_stb_i(ring0_stb_i),
- .wbs_cyc_i(ring0_cyc_i),
- .wbs_we_i(ring0_we_i),
- .wbs_sel_i(ring0_sel_i),
- .wbs_dat_i(ring0_dat_i),
- .wbs_adr_i(ring0_adr_i),
+ .wb_stb_i(ring0_stb_i),
+ .wb_cyc_i(ring0_cyc_i),
+ .wb_we_i(ring0_we_i),
+ .wb_sel_i(ring0_sel_i),
+ .wb_dat_i(ring0_dat_i),
+ .wb_adr_i(ring0_adr_i),
- .wbs_ack_o(ring0_ack_o),
- .wbs_dat_o(ring0_dat_o),
+ .wb_ack_o(ring0_ack_o),
+ .wb_dat_o(ring0_dat_o),
.ring_clk(ring0_clk),
.ring_start(ring0_start),
@@ -228,23 +229,17 @@
.ring_clkmux(ring0_clkmux)
);
- collapsering_macro collapsering0 (
- .CLKBUFOUT(ring0_clk),
- .START(ring0_start),
- .TRIMA(ring0_trim_a),
- .TRIMB(ring0_trim_b),
- .CLKMUX(ring0_clkmux)
- );
-
// Connect up external ports.
assign gpio_in = io_in[37:6];
- assign io_out[5:0] = 6'b0;
+ assign uart_rx = io_in[2];
+
+ assign io_out[5:0] = {1'b0, uart_tx, 4'b0};
assign io_out[37:6] = gpio_out;
- assign io_oeb[5:0] = {6{1'b1}};
+ assign io_oeb[5:0] = {1'b1, ~uart_enabled, 4'b1};
assign io_oeb[37:6] = gpio_oeb;
assign la_data_out = 128'b0;
assign irq = 3'b0;
-endmodule // module dtop
+endmodule // module digitalcore_macro
diff --git a/ip/randsack/rtl/ring_control.v b/ip/randsack/rtl/ring_control.v
index 002b918..5efe222 100644
--- a/ip/randsack/rtl/ring_control.v
+++ b/ip/randsack/rtl/ring_control.v
@@ -22,15 +22,15 @@
input wb_clk_i,
input wb_rst_i,
- input wbs_stb_i,
- input wbs_cyc_i,
- input wbs_we_i,
- input [3:0] wbs_sel_i,
- input [31:0] wbs_dat_i,
- input [31:0] wbs_adr_i,
+ input wb_stb_i,
+ input wb_cyc_i,
+ input wb_we_i,
+ input [3:0] wb_sel_i,
+ input [31:0] wb_dat_i,
+ input [31:0] wb_adr_i,
- output reg wbs_ack_o,
- output reg [31:0] wbs_dat_o,
+ output reg wb_ack_o,
+ output reg [31:0] wb_dat_o,
input ring_clk,
output reg ring_start,
@@ -50,10 +50,10 @@
wire slave_sel = (wb_stb_i && wb_cyc_i);
wire slave_write_en = (|wb_sel_i && wb_we_i);
- wire control_sel = |(wb_adr_i[7:0] & CONTROL_ADDR);
- wire count_value_sel = |(wb_adr_i[7:0] & COUNT_VALUE_ADDR);
- wire trima_sel = |(wb_adr_i[7:0] & TRIMA_ADDR);
- wire trimb_sel = |(wb_adr_i[7:0] & TRIMB_ADDR);
+ wire control_sel = (wb_adr_i[7:0] == CONTROL_ADDR);
+ wire count_value_sel = (wb_adr_i[7:0] == COUNT_VALUE_ADDR);
+ wire trima_sel = (wb_adr_i[7:0] == TRIMA_ADDR);
+ wire trimb_sel = (wb_adr_i[7:0] == TRIMB_ADDR);
// Counter signals and regs.
reg counter_resetb;
@@ -78,8 +78,8 @@
counter_resetb <= 1'b0;
ring_start <= 1'b0;
ring_clkmux <= {CLKMUX_BITS{1'b1}};
- ring_trim_a <= {TRIM_BITS{1b'1}};
- ring_trim_b <= {TRIM_BITS{1b'1}};
+ ring_trim_a <= {TRIM_BITS{1'b1}};
+ ring_trim_b <= {TRIM_BITS{1'b1}};
end else begin
wb_ack_o <= 1'b0;
@@ -87,7 +87,7 @@
wb_ack_o <= 1'b1;
if (control_sel) begin
- counter_resetb <= wb_dat_i[0];
+ counter_resetb <= ~wb_dat_i[0];
ring_start <= wb_dat_i[1];
ring_clkmux <= wb_dat_i[CLKMUX_BITS-1+8:8];
end else if (trima_sel) begin
diff --git a/ip/third_party/picorv32_wb/simpleuart.v b/ip/third_party/picorv32_wb/simpleuart_div16_wb.v
similarity index 94%
rename from ip/third_party/picorv32_wb/simpleuart.v
rename to ip/third_party/picorv32_wb/simpleuart_div16_wb.v
index 4fe9f0c..9e5d66f 100644
--- a/ip/third_party/picorv32_wb/simpleuart.v
+++ b/ip/third_party/picorv32_wb/simpleuart_div16_wb.v
@@ -18,7 +18,7 @@
*
*/
-module simpleuart_wb # (
+module simpleuart_div16_wb # (
parameter BASE_ADR = 32'h 2000_0000,
parameter CLK_DIV = 8'h00,
parameter DATA = 8'h04,
@@ -66,7 +66,7 @@
assign wb_ack_o = (simpleuart_reg_div_sel || simpleuart_reg_dat_sel
|| simpleuart_reg_cfg_sel) && (!reg_dat_wait);
- simpleuart simpleuart (
+ simpleuart_div16 simpleuart_div16 (
.clk (wb_clk_i),
.resetn (resetn),
@@ -91,7 +91,7 @@
endmodule
-module simpleuart (
+module simpleuart_div16 (
input clk,
input resetn,
@@ -113,18 +113,18 @@
output [31:0] reg_dat_do,
output reg_dat_wait
);
- reg [31:0] cfg_divider;
+ reg [15:0] cfg_divider;
reg enabled;
reg [3:0] recv_state;
- reg [31:0] recv_divcnt;
+ reg [15:0] recv_divcnt;
reg [7:0] recv_pattern;
reg [7:0] recv_buf_data;
reg recv_buf_valid;
reg [9:0] send_pattern;
reg [3:0] send_bitcnt;
- reg [31:0] send_divcnt;
+ reg [15:0] send_divcnt;
reg send_dummy;
wire reg_ena_do;
@@ -142,8 +142,8 @@
end else begin
if (reg_div_we[0]) cfg_divider[ 7: 0] <= reg_div_di[ 7: 0];
if (reg_div_we[1]) cfg_divider[15: 8] <= reg_div_di[15: 8];
- if (reg_div_we[2]) cfg_divider[23:16] <= reg_div_di[23:16];
- if (reg_div_we[3]) cfg_divider[31:24] <= reg_div_di[31:24];
+ // if (reg_div_we[2]) cfg_divider[23:16] <= reg_div_di[23:16];
+ // if (reg_div_we[3]) cfg_divider[31:24] <= reg_div_di[31:24];
if (reg_cfg_we) enabled <= reg_div_di[0];
end
end
diff --git a/openlane/digitalcore_macro/base.sdc b/openlane/digitalcore_macro/base.sdc
index 28171c8..5efe131 100644
--- a/openlane/digitalcore_macro/base.sdc
+++ b/openlane/digitalcore_macro/base.sdc
@@ -1,9 +1,31 @@
+# Randsack digital top macro timing constraints.
+#
+# SPDX-FileCopyrightText: (c) 2021 Harrison Pham <harrison@harrisonpham.com>
+# SPDX-License-Identifier: Apache-2.0
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
-if {[info exists ::env(CLOCK_PORT)] && $::env(CLOCK_PORT) != ""} {
- create_clock [get_ports $::env(CLOCK_PORT)] -name $::env(CLOCK_PORT) -period $::env(CLOCK_PERIOD)
+set ::env(WB_CLOCK_PERIOD) "10"
+set ::env(WB_CLOCK_PORT) "wb_clk_i"
+
+set ::env(RING0_CLOCK_PERIOD) "10"
+set ::env(RING0_CLOCK_PORT) "ring0_clk"
+
+if {[info exists ::env(WB_CLOCK_PORT)] && $::env(WB_CLOCK_PORT) != ""} {
+ create_clock [get_ports $::env(WB_CLOCK_PORT)] -name $::env(WB_CLOCK_PORT) -period $::env(CLOCK_PERIOD)
} else {
create_clock -name VIRTUAL_CLK -period $::env(CLOCK_PERIOD)
- set ::env(CLOCK_PORT) VIRTUAL_CLK
+ set ::env(WB_CLOCK_PORT) VIRTUAL_CLK
}
set input_delay_value [expr $::env(CLOCK_PERIOD) * $::env(IO_PCT)]
set output_delay_value [expr $::env(CLOCK_PERIOD) * $::env(IO_PCT)]
@@ -12,7 +34,7 @@
set_max_fanout $::env(SYNTH_MAX_FANOUT) [current_design]
-set clk_indx [lsearch [all_inputs] [get_port $::env(CLOCK_PORT)]]
+set clk_indx [lsearch [all_inputs] [get_port $::env(WB_CLOCK_PORT)]]
#set rst_indx [lsearch [all_inputs] [get_port resetn]]
set all_inputs_wo_clk [lreplace [all_inputs] $clk_indx $clk_indx]
#set all_inputs_wo_clk_rst [lreplace $all_inputs_wo_clk $rst_indx $rst_indx]
@@ -20,12 +42,16 @@
# correct resetn
-set_input_delay $input_delay_value -clock [get_clocks $::env(CLOCK_PORT)] $all_inputs_wo_clk_rst
-#set_input_delay 0.0 -clock [get_clocks $::env(CLOCK_PORT)] {resetn}
-set_output_delay $output_delay_value -clock [get_clocks $::env(CLOCK_PORT)] [all_outputs]
+set_input_delay $input_delay_value -clock [get_clocks $::env(WB_CLOCK_PORT)] $all_inputs_wo_clk_rst
+#set_input_delay 0.0 -clock [get_clocks $::env(WB_CLOCK_PORT)] {resetn}
+set_output_delay $output_delay_value -clock [get_clocks $::env(WB_CLOCK_PORT)] [all_outputs]
# TODO set this as parameter
set_driving_cell -lib_cell $::env(SYNTH_DRIVING_CELL) -pin $::env(SYNTH_DRIVING_CELL_PIN) [all_inputs]
set cap_load [expr $::env(SYNTH_CAP_LOAD) / 1000.0]
puts "\[INFO\]: Setting load to: $cap_load"
set_load $cap_load [all_outputs]
+
+# Extra clocks for macros.
+# NOTE: These don't need any input/output delays since this design just uses it for clock counting.
+create_clock [get_ports $::env(RING0_CLOCK_PORT)] -name $::env(RING0_CLOCK_PORT) -period $::env(RING0_CLOCK_PERIOD)
diff --git a/openlane/digitalcore_macro/config.tcl b/openlane/digitalcore_macro/config.tcl
index 8f6a898..76c41aa 100755
--- a/openlane/digitalcore_macro/config.tcl
+++ b/openlane/digitalcore_macro/config.tcl
@@ -19,23 +19,28 @@
set ::env(VERILOG_FILES) "\
$::env(CARAVEL_ROOT)/verilog/rtl/defines.v \
- $script_dir/../../ip/randsack/dtop.v"
+ $script_dir/../../ip/randsack/rtl/digitalcore_macro.v \
+ $script_dir/../../ip/third_party/picorv32_wb/gpio32_wb.v \
+ $script_dir/../../ip/third_party/picorv32_wb/simpleuart_div16_wb.v \
+ $script_dir/../../ip/third_party/verilog-wishbone/rtl/wb_mux_3.v \
+ $script_dir/../../ip/randsack/rtl/ring_control.v"
set ::env(DESIGN_IS_CORE) 0
+set ::env(SDC_FILE) "$script_dir/base.sdc"
set ::env(BASE_SDC_FILE) "$script_dir/base.sdc"
-set ::env(CLOCK_PORT) "wb_clk_i"
-# set ::env(CLOCK_NET) "counter.clk"
+# NOTE: Make sure to add all clocks manually to base.sdc!
+set ::env(CLOCK_PORT) "wb_clk_i ring0_clk"
set ::env(CLOCK_PERIOD) "10"
set ::env(FP_SIZING) absolute
-set ::env(DIE_AREA) "0 0 1000 1000"
+set ::env(DIE_AREA) "0 0 500 500"
set ::env(FP_PIN_ORDER_CFG) $script_dir/pin_order.cfg
-set ::env(PL_BASIC_PLACEMENT) 1
-set ::env(PL_TARGET_DENSITY) 0.3
+set ::env(PL_TIME_DRIVEN) 1
+set ::env(PL_TARGET_DENSITY) 0.4
# Maximum layer used for routing is metal 4.
# This is because this macro will be inserted in a top level (user_project_wrapper)
@@ -50,3 +55,5 @@
set ::env(DIODE_INSERTION_STRATEGY) 4
# If you're going to use multiple power domains, then disable cvc run.
set ::env(RUN_CVC) 1
+
+set ::env(ROUTING_CORES) 10
diff --git a/openlane/digitalcore_macro/pin_order.cfg b/openlane/digitalcore_macro/pin_order.cfg
index 2fda806..14412b6 100644
--- a/openlane/digitalcore_macro/pin_order.cfg
+++ b/openlane/digitalcore_macro/pin_order.cfg
@@ -8,3 +8,12 @@
#N
io_.*
+
+#E
+
+#W
+ring.*_trim_a.*
+ring.*_trim_b.*
+ring.*_clkmux.*
+ring.*_clk_out
+ring.*_start
diff --git a/verilog/dv/randsack_netlists.v b/verilog/dv/randsack_netlists.v
new file mode 100644
index 0000000..2eb9750
--- /dev/null
+++ b/verilog/dv/randsack_netlists.v
@@ -0,0 +1,32 @@
+// SPDX-FileCopyrightText: 2020 Efabless Corporation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+// SPDX-License-Identifier: Apache-2.0
+
+// Include caravel global defines for the number of the user project IO pads
+`include "defines.v"
+`define USE_POWER_PINS
+
+`ifdef GL
+ // Assume default net type to be wire because GL netlists don't have the wire definitions
+ `default_nettype wire
+ `include "gl/user_project_wrapper.v"
+`else
+ `include "user_project_wrapper.v"
+ `include "digitalcore_macro.v"
+ `include "collapsering_macro.v"
+ `include "ring_control.v"
+ `include "picorv32_wb/gpio32_wb.v"
+ `include "picorv32_wb/simpleuart_div16_wb.v"
+ `include "verilog-wishbone/rtl/wb_mux_3.v"
+`endif
diff --git a/verilog/dv/randsack_regrw_directed/Makefile b/verilog/dv/randsack_regrw_directed/Makefile
new file mode 100644
index 0000000..07e13f7
--- /dev/null
+++ b/verilog/dv/randsack_regrw_directed/Makefile
@@ -0,0 +1,100 @@
+# SPDX-FileCopyrightText: 2020 Efabless Corporation
+#
+# Licensed under the Apache License, Version 2.0 (the "License");
+# you may not use this file except in compliance with the License.
+# You may obtain a copy of the License at
+#
+# http://www.apache.org/licenses/LICENSE-2.0
+#
+# Unless required by applicable law or agreed to in writing, software
+# distributed under the License is distributed on an "AS IS" BASIS,
+# WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+# See the License for the specific language governing permissions and
+# limitations under the License.
+#
+# SPDX-License-Identifier: Apache-2.0
+
+## PDK
+PDK_PATH = $(PDK_ROOT)/sky130A
+
+## Caravel Pointers
+CARAVEL_ROOT ?= ../../../caravel
+CARAVEL_PATH ?= $(CARAVEL_ROOT)
+CARAVEL_FIRMWARE_PATH = $(CARAVEL_PATH)/verilog/dv/caravel
+CARAVEL_VERILOG_PATH = $(CARAVEL_PATH)/verilog
+CARAVEL_RTL_PATH = $(CARAVEL_VERILOG_PATH)/rtl
+CARAVEL_BEHAVIOURAL_MODELS = $(CARAVEL_VERILOG_PATH)/dv/caravel
+
+## User Project Pointers
+UPRJ_VERILOG_PATH ?= ../../../verilog
+UPRJ_RTL_PATH = $(UPRJ_VERILOG_PATH)/rtl
+UPRJ_BEHAVIOURAL_MODELS = ../../../ip/randsack/rtl
+
+## Third party IP
+THIRD_PARTY_IP = ../../../ip/third_party
+
+## RISCV GCC
+GCC_PATH?=/ef/apps/bin
+GCC_PREFIX?=riscv32-unknown-elf
+
+## Simulation mode: RTL/GL
+SIM_DEFINES = -DFUNCTIONAL -DSIM
+SIM?=RTL
+
+.SUFFIXES:
+
+PATTERN = randsack_regrw_directed
+
+all: ${PATTERN:=.vcd}
+
+hex: ${PATTERN:=.hex}
+
+%.vvp: %_tb.v %.hex
+ifeq ($(SIM),RTL)
+ iverilog $(SIM_DEFINES) -I $(PDK_PATH) \
+ -I $(CARAVEL_BEHAVIOURAL_MODELS) -I $(CARAVEL_RTL_PATH) \
+ -I $(UPRJ_BEHAVIOURAL_MODELS) -I $(UPRJ_RTL_PATH) \
+ -I $(THIRD_PARTY_IP) \
+ $< -o $@
+else
+ iverilog $(SIM_DEFINES) -DGL -I $(PDK_PATH) \
+ -I $(CARAVEL_BEHAVIOURAL_MODELS) -I $(CARAVEL_RTL_PATH) -I $(CARAVEL_VERILOG_PATH) \
+ -I $(UPRJ_BEHAVIOURAL_MODELS) -I$(UPRJ_RTL_PATH) -I $(UPRJ_VERILOG_PATH) \
+ $< -o $@
+endif
+
+%.vcd: %.vvp
+ vvp $<
+
+%.elf: %.c $(CARAVEL_FIRMWARE_PATH)/sections.lds $(CARAVEL_FIRMWARE_PATH)/start.s check-env
+ ${GCC_PATH}/${GCC_PREFIX}-gcc -I $(CARAVEL_PATH) -march=rv32imc -mabi=ilp32 -Wl,-Bstatic,-T,$(CARAVEL_FIRMWARE_PATH)/sections.lds,--strip-debug -ffreestanding -nostdlib -o $@ $(CARAVEL_FIRMWARE_PATH)/start.s $<
+
+%.hex: %.elf
+ ${GCC_PATH}/${GCC_PREFIX}-objcopy -O verilog $< $@
+ # to fix flash base address
+ sed -i 's/@10000000/@00000000/g' $@
+
+%.bin: %.elf
+ ${GCC_PATH}/${GCC_PREFIX}-objcopy -O binary $< /dev/stdout | tail -c +1048577 > $@
+
+check-env:
+ifndef PDK_ROOT
+ $(error PDK_ROOT is undefined, please export it before running make)
+endif
+ifeq (,$(wildcard $(PDK_ROOT)/sky130A))
+ $(error $(PDK_ROOT)/sky130A not found, please install pdk before running make)
+endif
+ifeq (,$(wildcard $(GCC_PATH)/$(GCC_PREFIX)-gcc ))
+ $(error $(GCC_PATH)/$(GCC_PREFIX)-gcc is not found, please export GCC_PATH and GCC_PREFIX before running make)
+endif
+# check for efabless style installation
+ifeq (,$(wildcard $(PDK_ROOT)/sky130A/libs.ref/*/verilog))
+SIM_DEFINES := ${SIM_DEFINES} -DEF_STYLE
+endif
+
+# ---- Clean ----
+
+clean:
+ rm -f *.elf *.hex *.bin *.vvp *.vcd *.log
+
+.PHONY: clean hex all
diff --git a/verilog/dv/randsack_regrw_directed/randsack_regrw_directed.c b/verilog/dv/randsack_regrw_directed/randsack_regrw_directed.c
new file mode 100644
index 0000000..2218b98
--- /dev/null
+++ b/verilog/dv/randsack_regrw_directed/randsack_regrw_directed.c
@@ -0,0 +1,97 @@
+/*
+ * SPDX-FileCopyrightText: 2020 Efabless Corporation
+ *
+ * Licensed under the Apache License, Version 2.0 (the "License");
+ * you may not use this file except in compliance with the License.
+ * You may obtain a copy of the License at
+ *
+ * http://www.apache.org/licenses/LICENSE-2.0
+ *
+ * Unless required by applicable law or agreed to in writing, software
+ * distributed under the License is distributed on an "AS IS" BASIS,
+ * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+ * See the License for the specific language governing permissions and
+ * limitations under the License.
+ * SPDX-License-Identifier: Apache-2.0
+ */
+
+// This include is relative to $CARAVEL_PATH (see Makefile)
+#include "verilog/dv/caravel/defs.h"
+#include "verilog/dv/caravel/stub.c"
+
+#define REG(addr) (*(volatile uint32_t*)(addr))
+
+#define RANDSACK_GPIO0_BASE 0x30800000
+#define RANDSACK_PWM0_BASE 0x30810000
+#define RANDSACK_UART0_BASE 0x30820000
+#define RANDSACK_RING0_BASE 0x30830000
+
+#define RANDSACK_GPIO_DATA 0x00
+#define RANDSACK_GPIO_ENA 0x04
+#define RANDSACK_GPIO_PU 0x08
+#define RANDSACK_GPIO_PD 0x0c
+
+#define RANDSACK_RING_COUNT_ADDR 0x00
+#define RANDSACK_RING_CONTROL_ADDR 0x04
+#define RANDSACK_RING_TRIMA_ADDR 0x08
+#define RANDSACK_RING_TRIMB_ADDR 0x0c
+
+#define RANDSACK_RING_CONTROL_RESET_MASK (1 << 0)
+#define RANDSACK_RING_CONTROL_START_MASK (1 << 1)
+
+int i = 0;
+int clk = 0;
+
+void main() {
+ /* Set up the housekeeping SPI to be connected internally so */
+ /* that external pin changes don't affect it. */
+
+ reg_spimaster_config = 0xa002; // Enable, prescaler = 2,
+ // connect to housekeeping SPI
+
+ // Connect the housekeeping SPI to the SPI master
+ // so that the CSB line is not left floating. This allows
+ // all of the GPIO pins to be used for user functions.
+
+ reg_mprj_io_37 = GPIO_MODE_USER_STD_BIDIRECTIONAL;
+ reg_mprj_io_36 = GPIO_MODE_USER_STD_BIDIRECTIONAL;
+ reg_mprj_io_35 = GPIO_MODE_USER_STD_BIDIRECTIONAL;
+ reg_mprj_io_34 = GPIO_MODE_USER_STD_BIDIRECTIONAL;
+ reg_mprj_io_33 = GPIO_MODE_USER_STD_BIDIRECTIONAL;
+ reg_mprj_io_32 = GPIO_MODE_USER_STD_BIDIRECTIONAL;
+ reg_mprj_io_31 = GPIO_MODE_USER_STD_BIDIRECTIONAL;
+ reg_mprj_io_30 = GPIO_MODE_USER_STD_BIDIRECTIONAL;
+ reg_mprj_io_29 = GPIO_MODE_USER_STD_BIDIRECTIONAL;
+ reg_mprj_io_28 = GPIO_MODE_USER_STD_BIDIRECTIONAL;
+ reg_mprj_io_27 = GPIO_MODE_USER_STD_BIDIRECTIONAL;
+ reg_mprj_io_26 = GPIO_MODE_USER_STD_BIDIRECTIONAL;
+ reg_mprj_io_25 = GPIO_MODE_USER_STD_BIDIRECTIONAL;
+ reg_mprj_io_24 = GPIO_MODE_USER_STD_BIDIRECTIONAL;
+ reg_mprj_io_23 = GPIO_MODE_USER_STD_BIDIRECTIONAL;
+ reg_mprj_io_22 = GPIO_MODE_USER_STD_BIDIRECTIONAL;
+
+ /* Apply configuration */
+ reg_mprj_xfer = 1;
+ while (reg_mprj_xfer == 1)
+ ;
+
+ // Enable GPIOs and write pattern.
+ REG(RANDSACK_GPIO0_BASE + RANDSACK_GPIO_ENA) = 0xffff0000;
+ REG(RANDSACK_GPIO0_BASE + RANDSACK_GPIO_DATA) = 0x55550000;
+
+ // Reset ring osc.
+ REG(RANDSACK_RING0_BASE + RANDSACK_RING_CONTROL_ADDR) = RANDSACK_RING_CONTROL_RESET_MASK;
+ REG(RANDSACK_RING0_BASE + RANDSACK_RING_CONTROL_ADDR) = 0;
+
+ // Start ring osc.
+ REG(RANDSACK_RING0_BASE + RANDSACK_RING_CONTROL_ADDR) = RANDSACK_RING_CONTROL_START_MASK;
+
+ REG(RANDSACK_GPIO0_BASE + RANDSACK_GPIO_DATA) = 0xaaaa0000;
+
+ // Wait for valid value.
+ while (REG(RANDSACK_RING0_BASE + RANDSACK_RING_COUNT_ADDR) < 100) {
+ REG(RANDSACK_GPIO0_BASE + RANDSACK_GPIO_DATA) = 0xdead0000;
+ }
+
+ REG(RANDSACK_GPIO0_BASE + RANDSACK_GPIO_DATA) = 0xfeed0000;
+}
diff --git a/verilog/dv/randsack_regrw_directed/randsack_regrw_directed_tb.v b/verilog/dv/randsack_regrw_directed/randsack_regrw_directed_tb.v
new file mode 100644
index 0000000..ef24cb6
--- /dev/null
+++ b/verilog/dv/randsack_regrw_directed/randsack_regrw_directed_tb.v
@@ -0,0 +1,154 @@
+// SPDX-FileCopyrightText: 2020 Efabless Corporation
+//
+// Licensed under the Apache License, Version 2.0 (the "License");
+// you may not use this file except in compliance with the License.
+// You may obtain a copy of the License at
+//
+// http://www.apache.org/licenses/LICENSE-2.0
+//
+// Unless required by applicable law or agreed to in writing, software
+// distributed under the License is distributed on an "AS IS" BASIS,
+// WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
+// See the License for the specific language governing permissions and
+// limitations under the License.
+// SPDX-License-Identifier: Apache-2.0
+
+`default_nettype none
+
+`timescale 1 ns / 1 ps
+
+`include "../randsack_netlists.v"
+`include "caravel_netlists.v"
+`include "spiflash.v"
+
+module randsack_regrw_directed_tb;
+ reg clock;
+ reg RSTB;
+ reg CSB;
+ reg power1, power2;
+ reg power3, power4;
+
+ wire gpio;
+ wire [37:0] mprj_io;
+ wire [15:0] checkbits;
+
+ assign checkbits = mprj_io[37:22];
+
+ // Force housekeeping SPI.
+ assign mprj_io[3] = (CSB == 1'b1) ? 1'b1 : 1'bz;
+
+ // External clock is used by default. Make this artificially fast for the
+ // simulation. Normally this would be a slow clock and the digital PLL
+ // would be the fast clock.
+
+ always #12.5 clock <= (clock === 1'b0);
+
+ initial begin
+ clock = 0;
+ end
+
+ initial begin
+ $dumpfile("randsack_regrw_directed_tb.vcd");
+ $dumpvars(0, randsack_regrw_directed_tb);
+
+ // Repeat cycles of 1000 clock edges as needed to complete testbench
+ repeat (30) begin
+ repeat (1000) @(posedge clock);
+ // $display("+1000 cycles");
+ end
+ $fatal(2, "FAILED: Timed out.");
+ end
+
+ initial begin
+ wait(checkbits == 16'h5555);
+ $display("Monitor: GPIO started");
+ wait(checkbits == 16'haaaa);
+ $display("Monitor: GPIO first write okay");
+ wait(checkbits == 16'hfeed);
+ `ifdef GL
+ $display("Monitor: GPIO GL finished");
+ `else
+ $display("Monitor: GPIO RTL finished");
+ `endif
+ #1000;
+ $finish;
+ end
+
+ initial begin
+ RSTB <= 1'b0;
+ CSB <= 1'b1; // Force CSB high
+ #2000;
+ RSTB <= 1'b1; // Release reset
+ #170000;
+ CSB = 1'b0; // CSB can be released
+ end
+
+ // Power-up sequence
+ initial begin
+ power1 <= 1'b0;
+ power2 <= 1'b0;
+ power3 <= 1'b0;
+ power4 <= 1'b0;
+ #100;
+ power1 <= 1'b1;
+ #100;
+ power2 <= 1'b1;
+ #100;
+ power3 <= 1'b1;
+ #100;
+ power4 <= 1'b1;
+ end
+
+ always @(mprj_io) begin
+ #1 $display("MPRJ-IO state = %b ", mprj_io);
+ end
+
+ wire flash_csb;
+ wire flash_clk;
+ wire flash_io0;
+ wire flash_io1;
+
+ wire VDD3V3 = power1;
+ wire VDD1V8 = power2;
+ wire USER_VDD3V3 = power3;
+ wire USER_VDD1V8 = power4;
+ wire VSS = 1'b0;
+
+ caravel uut (
+ .vddio(VDD3V3),
+ .vssio(VSS),
+ .vdda(VDD3V3),
+ .vssa(VSS),
+ .vccd(VDD1V8),
+ .vssd(VSS),
+ .vdda1(USER_VDD3V3),
+ .vdda2(USER_VDD3V3),
+ .vssa1(VSS),
+ .vssa2(VSS),
+ .vccd1(USER_VDD1V8),
+ .vccd2(USER_VDD1V8),
+ .vssd1(VSS),
+ .vssd2(VSS),
+ .clock(clock),
+ .gpio(gpio),
+ .mprj_io(mprj_io),
+ .flash_csb(flash_csb),
+ .flash_clk(flash_clk),
+ .flash_io0(flash_io0),
+ .flash_io1(flash_io1),
+ .resetb(RSTB)
+ );
+
+ spiflash #(
+ .FILENAME("randsack_regrw_directed.hex")
+ ) spiflash (
+ .csb(flash_csb),
+ .clk(flash_clk),
+ .io0(flash_io0),
+ .io1(flash_io1),
+ .io2(),
+ .io3()
+ );
+
+endmodule
+`default_nettype wire
diff --git a/verilog/rtl/user_project_wrapper.v b/verilog/rtl/user_project_wrapper.v
index 5ee1cee..646c96d 100644
--- a/verilog/rtl/user_project_wrapper.v
+++ b/verilog/rtl/user_project_wrapper.v
@@ -30,92 +30,110 @@
*/
module user_project_wrapper #(
- parameter BITS = 32
+ parameter BITS = 32
) (
`ifdef USE_POWER_PINS
- inout vdda1, // User area 1 3.3V supply
- inout vdda2, // User area 2 3.3V supply
- inout vssa1, // User area 1 analog ground
- inout vssa2, // User area 2 analog ground
- inout vccd1, // User area 1 1.8V supply
- inout vccd2, // User area 2 1.8v supply
- inout vssd1, // User area 1 digital ground
- inout vssd2, // User area 2 digital ground
+ inout vdda1, // User area 1 3.3V supply
+ inout vdda2, // User area 2 3.3V supply
+ inout vssa1, // User area 1 analog ground
+ inout vssa2, // User area 2 analog ground
+ inout vccd1, // User area 1 1.8V supply
+ inout vccd2, // User area 2 1.8v supply
+ inout vssd1, // User area 1 digital ground
+ inout vssd2, // User area 2 digital ground
`endif
- // Wishbone Slave ports (WB MI A)
- input wb_clk_i,
- input wb_rst_i,
- input wbs_stb_i,
- input wbs_cyc_i,
- input wbs_we_i,
- input [3:0] wbs_sel_i,
- input [31:0] wbs_dat_i,
- input [31:0] wbs_adr_i,
- output wbs_ack_o,
- output [31:0] wbs_dat_o,
+ // Wishbone Slave ports (WB MI A)
+ input wb_clk_i,
+ input wb_rst_i,
+ input wbs_stb_i,
+ input wbs_cyc_i,
+ input wbs_we_i,
+ input [3:0] wbs_sel_i,
+ input [31:0] wbs_dat_i,
+ input [31:0] wbs_adr_i,
+ output wbs_ack_o,
+ output [31:0] wbs_dat_o,
- // Logic Analyzer Signals
- input [127:0] la_data_in,
- output [127:0] la_data_out,
- input [127:0] la_oenb,
+ // Logic Analyzer Signals
+ input [127:0] la_data_in,
+ output [127:0] la_data_out,
+ input [127:0] la_oenb,
- // IOs
- input [`MPRJ_IO_PADS-1:0] io_in,
- output [`MPRJ_IO_PADS-1:0] io_out,
- output [`MPRJ_IO_PADS-1:0] io_oeb,
+ // IOs
+ input [`MPRJ_IO_PADS-1:0] io_in,
+ output [`MPRJ_IO_PADS-1:0] io_out,
+ output [`MPRJ_IO_PADS-1:0] io_oeb,
- // Analog (direct connection to GPIO pad---use with caution)
- // Note that analog I/O is not available on the 7 lowest-numbered
- // GPIO pads, and so the analog_io indexing is offset from the
- // GPIO indexing by 7 (also upper 2 GPIOs do not have analog_io).
- inout [`MPRJ_IO_PADS-10:0] analog_io,
+ // Analog (direct connection to GPIO pad---use with caution)
+ // Note that analog I/O is not available on the 7 lowest-numbered
+ // GPIO pads, and so the analog_io indexing is offset from the
+ // GPIO indexing by 7 (also upper 2 GPIOs do not have analog_io).
+ inout [`MPRJ_IO_PADS-10:0] analog_io,
- // Independent clock (on independent integer divider)
- input user_clock2,
+ // Independent clock (on independent integer divider)
+ input user_clock2,
- // User maskable interrupt signals
- output [2:0] user_irq
+ // User maskable interrupt signals
+ output [2:0] user_irq
);
/*--------------------------------------*/
/* User project is instantiated here */
/*--------------------------------------*/
-user_proj_example mprj (
+ wire ring0_clk;
+ wire ring0_start;
+ wire [27:0] ring0_trim_a;
+ wire [27:0] ring0_trim_b;
+ wire [2:0] ring0_clkmux;
+
+digitalcore_macro mprj (
`ifdef USE_POWER_PINS
- .vccd1(vccd1), // User area 1 1.8V power
- .vssd1(vssd1), // User area 1 digital ground
+ .vccd1(vccd1), // User area 1 1.8V power
+ .vssd1(vssd1), // User area 1 digital ground
`endif
- .wb_clk_i(wb_clk_i),
- .wb_rst_i(wb_rst_i),
+ .wb_clk_i(wb_clk_i),
+ .wb_rst_i(wb_rst_i),
- // MGMT SoC Wishbone Slave
+ // MGMT SoC Wishbone Slave
+ .wbs_cyc_i(wbs_cyc_i),
+ .wbs_stb_i(wbs_stb_i),
+ .wbs_we_i(wbs_we_i),
+ .wbs_sel_i(wbs_sel_i),
+ .wbs_adr_i(wbs_adr_i),
+ .wbs_dat_i(wbs_dat_i),
+ .wbs_ack_o(wbs_ack_o),
+ .wbs_dat_o(wbs_dat_o),
- .wbs_cyc_i(wbs_cyc_i),
- .wbs_stb_i(wbs_stb_i),
- .wbs_we_i(wbs_we_i),
- .wbs_sel_i(wbs_sel_i),
- .wbs_adr_i(wbs_adr_i),
- .wbs_dat_i(wbs_dat_i),
- .wbs_ack_o(wbs_ack_o),
- .wbs_dat_o(wbs_dat_o),
+ // Logic Analyzer
+ .la_data_in(la_data_in),
+ .la_data_out(la_data_out),
+ .la_oenb (la_oenb),
- // Logic Analyzer
+ // IO Pads
+ .io_in (io_in),
+ .io_out(io_out),
+ .io_oeb(io_oeb),
- .la_data_in(la_data_in),
- .la_data_out(la_data_out),
- .la_oenb (la_oenb),
+ // IRQ
+ .irq(user_irq),
- // IO Pads
+ // ring0 collapsering macro
+ .ring0_clk(ring0_clk),
+ .ring0_start(ring0_start),
+ .ring0_trim_a(ring0_trim_a),
+ .ring0_trim_b(ring0_trim_b),
+ .ring0_clkmux(ring0_clkmux)
+);
- .io_in (io_in),
- .io_out(io_out),
- .io_oeb(io_oeb),
-
- // IRQ
- .irq(user_irq)
+collapsering_macro collapsering0 (
+ .clk_out(ring0_clk),
+ .start(ring0_start),
+ .trim_a(ring0_trim_a),
+ .trim_b(ring0_trim_b),
+ .clkmux(ring0_clkmux)
);
endmodule // user_project_wrapper