gateware/icE1usb: Initial import of production hardware gateware

Current version has second E1 channel disabled to allow the
build to works. Works is in progress to optimize the gateware and
the fpga toolchain to allow full featured build.

Signed-off-by: Sylvain Munaut <tnt@246tNt.com>
This commit is contained in:
Sylvain Munaut 2020-09-15 22:11:29 +02:00
parent 035e247bf0
commit bd83e53ff6
13 changed files with 2116 additions and 0 deletions

4
gateware/icE1usb/.gitignore vendored Normal file
View File

@ -0,0 +1,4 @@
build-tmp
__pycache__
*.vcd
.*.swp

48
gateware/icE1usb/Makefile Normal file
View File

@ -0,0 +1,48 @@
# Project config
PROJ=icE1usb
PROJ_DEPS := no2e1 no2ice40 no2misc no2usb
PROJ_RTL_SRCS := $(addprefix rtl/, \
i2c_master.v \
i2c_master_wb.v \
led_blinker.v \
misc.v \
sr_btn_if.v \
sysmgr.v \
)
PROJ_RTL_SRCS += $(addprefix ../common/rtl/, \
dfu_helper.v \
picorv32.v \
soc_base.v \
soc_bram.v \
soc_iobuf.v \
soc_picorv32_bridge.v \
soc_spram.v \
wb_arbiter.v \
wb_dma.v \
wb_epbuf.v \
)
PROJ_PREREQ = \
$(BUILD_TMP)/boot.hex \
$(NULL)
PROJ_TOP_SRC := rtl/top.v
PROJ_TOP_MOD := top
# Target config
BOARD ?= ice1usb
DEVICE = up5k
PACKAGE = sg48
YOSYS_SYNTH_ARGS = -dffe_min_ce_use 4
NEXTPNR_ARGS = --pre-pack data/clocks.py --no-promote-globals --seed 2
# Include default rules
NO2BUILD_DIR := ../build
include $(NO2BUILD_DIR)/project-rules.mk
# Custom rules
../common/fw/boot.hex:
make -C ../common/fw boot.hex
$(BUILD_TMP)/boot.hex: ../common/fw/boot.hex
cp $< $@

View File

@ -0,0 +1,2 @@
ctx.addClock("clk_sys", 30.72)
ctx.addClock("clk_48m", 48)

View File

@ -0,0 +1,61 @@
# E1 PHY
set_io e1A_rx_hi_p 42
set_io e1A_rx_hi_n 38
set_io e1A_rx_lo_p 32
set_io e1A_rx_lo_n 31
set_io e1A_tx_hi 43
set_io e1A_tx_lo 36
set_io e1B_rx_hi_p 23
set_io e1B_rx_hi_n 25
set_io e1B_rx_lo_p 26
set_io e1B_rx_lo_n 27
set_io e1B_tx_hi 34
set_io e1B_tx_lo 37
set_io e1_rx_bias[0] 28
set_io e1_rx_bias[1] 35
# USB
set_io usb_dp 10
set_io usb_dn 9
set_io usb_pu 11
# Flash
set_io -pullup yes flash_mosi 14
set_io -pullup yes flash_miso 17
set_io -pullup yes flash_clk 15
set_io -pullup yes flash_cs_n 16
# LED Shift register + Button input
set_io -pullup yes e1_led_rclk 18
# GPS
set_io -pullup yes gps_reset_n 6
set_io -pullup yes gps_rx 47
set_io -pullup yes gps_tx 46
set_io gps_pps 2
# I2C
set_io i2c_sda 3
set_io i2c_scl 4
# GPIOs
set_io -pullup yes gpio[0] 13
set_io -pullup yes gpio[1] 20
set_io -pullup yes gpio[2] 19
# Clock
set_io clk_in 44
set_io clk_tune_hi 48
set_io clk_tune_lo 45
# Debug UART
set_io -pullup yes dbg_rx 21
set_io -pullup yes dbg_tx 12
# RGB LEDs
set_io rgb[0] 39
set_io rgb[1] 40
set_io rgb[2] 41

View File

@ -0,0 +1,329 @@
icE1usb-proto SoC Memory Map
============================
Overview
--------
| Base | Size | Description | IP Core doc
|-------------|------------------|-----------------|-------------
|`0x00000000` | `0x00400` (1k) | Boot ROM |
|`0x00020000` | `0x10000` (64k) | Main SRAM |
|`0x80000000` | | Flash SPI | [`no2ice40/ice40_spi_wb`](../../cores/no2ice40/doc/ice40_spi_wb.md)
|`0x81000000` | | Debug UART | [`no2misc/uart_wb`](../../cores/no2misc/doc/uart_wb.md)
|`0x82000000` | | RGB LED | [`no2ice40/ice40_rgb_wb`](../../cores/no2ice40/doc/ice40_rgb_wb.md)
|`0x83000000` | | USB core | [`no2usb`](../../cores/no2usb/doc/mem-map.md)
|`0x84000000` | `0x01000` (4k) | USB data buffer |
|`0x85000000` | `0x10000` (64k) | E1 data buffer |
|`0x86000000` | | DMA | See below
|`0x87000000` | | E1 core | [`no2e1`](../../cores/no2e1/doc/mem-map.md). See notes below.
|`0x88000000` | | Misc | See below
|`0x89000000` | | GPS UART | [`no2misc/uart_wb`](../../cores/no2misc/doc/uart_wb.md)
|`0x8a000000` | | I2C | See below
Memory
------
### `0x00000000`: Boot ROM
This memory zone is initialized directly in the FPGA bitstream itself.
It contains the bootstrap program that will load the main firmware from
flash into the main SRAM and jump to it.
### `0x00020000`: Main SRAM
The main SoC SRAM, implemented using the UP5k SPRAMs. It can't be initialized
in the FPGA bitstream directly, hence the need for the Boot ROM zone.
### `0x84000000`: USB data buffer
This 4k zone actually correspond to 8k of SRAM inside the USB core.
The RX and TX buffer for the USB are distinct and are accessed independently
depending if read or write access are made to this zone. (RX buffer can only
be read, TX buffer can only be written). All accesses must also be 32 bit
wide !
### `0x85000000`: E1 data buffer
This 64k buffer is reserved for E1 data and is what is used by the E1 core.
Address mapping is :
```text
,---------------------------------------------------------------,
| f | e | d | c | b | a | 9 | 8 | 7 | 6 | 5 | 4 | 3 | 2 | 1 | 0 |
|---------------------------------------------------------------|
| multi-frame | frame | timeslot |
'---------------------------------------------------------------'
```
and the `multi-frame` number is what is exchanged in the E1 core buffer
descriptors.
Custom Peripherals
------------------
### `0x86000000`: DMA
Very simple DMA core allowing direct copy of data between the USB and E1 data
buffers.
#### Status (Read Only, addr `0x00`)
```text
,-----------------------------------------------------------------------------------------------,
|31|30|29|28|27|26|25|24|23|22|21|20|19|18|17|16|15|14|13|12|11|10| 9| 8| 7| 6| 5| 4| 3| 2| 1| 0|
|-----------------------------------------------------------------------------------------------|
| / | b| d| /| len |
'-----------------------------------------------------------------------------------------------'
* [ 15] - b : Busy flag
* [ 14] - d : Direction ( 0=E1 to USB, 1=USB to E1 )
* [12: 0] - len : Remaining length of the in-progress transfer ( -1 = done )
```
#### Transfer start/direction/length (Write Only, addr `0x00`)
Write to this register initiate the transfer.
```text
,-----------------------------------------------------------------------------------------------,
|31|30|29|28|27|26|25|24|23|22|21|20|19|18|17|16|15|14|13|12|11|10| 9| 8| 7| 6| 5| 4| 3| 2| 1| 0|
|-----------------------------------------------------------------------------------------------|
| / | d| / | len |
'-----------------------------------------------------------------------------------------------'
* [ 14] - d : Direction ( 0=E1 to USB, 1=USB to E1 )
* [11: 0] - len : Transfer length ( Number of Words - 2 )
```
#### E1 buffer offset (Write Only, addr `0x08`)
```text
,-----------------------------------------------------------------------------------------------,
|31|30|29|28|27|26|25|24|23|22|21|20|19|18|17|16|15|14|13|12|11|10| 9| 8| 7| 6| 5| 4| 3| 2| 1| 0|
|-----------------------------------------------------------------------------------------------|
| / | e1_ofs |
'-----------------------------------------------------------------------------------------------'
* [13:0] - e1_ofs
```
Word offset inside the E1 data buffer where the next transfer will start
#### USB buffer offset (Write Only, addr `0x0C`)
```text
,-----------------------------------------------------------------------------------------------,
|31|30|29|28|27|26|25|24|23|22|21|20|19|18|17|16|15|14|13|12|11|10| 9| 8| 7| 6| 5| 4| 3| 2| 1| 0|
|-----------------------------------------------------------------------------------------------|
| / | usb_ofs |
'-----------------------------------------------------------------------------------------------'
* [9:0] - usb_ofs
```
Word offset inside the USB End Point buffer where the next transfer will start
### `0x87000000`: E1 core
Refer to the [`no2e1` core documentation](../../cores/no2e1/doc/mem-map.md)
for register description.
The core instanciated here has a 1 single channel containing both
RX and TX units.
### `0x88000000`: Misc
Collection of small auxiliary peripherals.
#### Boot (Write Only, addr `0x00`)
```text
,-----------------------------------------------------------------------------------------------,
|31|30|29|28|27|26|25|24|23|22|21|20|19|18|17|16|15|14|13|12|11|10| 9| 8| 7| 6| 5| 4| 3| 2| 1| 0|
|-----------------------------------------------------------------------------------------------|
| / | x| sel |
'-----------------------------------------------------------------------------------------------'
* [ 2] - d : boot eXecute
* [11:0] - sel : boot select
```
Write to this register with bit 2 set will trigger a FPGA reload of the selected image.
#### GPIO (Read/Write, addr `0x01`)
```text
,-----------------------------------------------------------------------------------------------,
|31|30|29|28|27|26|25|24|23|22|21|20|19|18|17|16|15|14|13|12|11|10| 9| 8| 7| 6| 5| 4| 3| 2| 1| 0|
|-----------------------------------------------------------------------------------------------|
| / | gpio_in | / | gpio_oe | / | gpio_out |
'-----------------------------------------------------------------------------------------------'
* [19:16] - gpio_in : Input
* [11: 8] - gpio_oe : Output Enable (0=Input, 1=Output)
* [ 3: 0] - gpio_out : Output
```
Note that `gpio[3]` is the `gps_reset_n` signal.
#### E1 connector LEDs (Read/Write, addr `0x02`)
```text
,-----------------------------------------------------------------------------------------------,
|31|30|29|28|27|26|25|24|23|22|21|20|19|18|17|16|15|14|13|12|11|10| 9| 8| 7| 6| 5| 4| 3| 2| 1| 0|
|-----------------------------------------------------------------------------------------------|
| / |ac|rn| yl1 | gn1 | yl0 | gn0 |
'-----------------------------------------------------------------------------------------------'
* [0] - ac : Refresh cycle active
* [8] - rn : Run refresh cycle
* [7:6] - yl1 : Chan 1 yellow led
* [5:4] - gn1 : Chan 1 green led
* [3:2] - yl0 : Chan 0 yellow led
* [1:0] - gn0 : Chan 0 green led
```
This register controls the unit that constantly refreshed the LED and also
polls the push button.
Note that because the pins are shared with flash SPI, this units need to be
disabled before any SPI access to flash ! To do so, set `rn` bit to `0`, then
wait for `ac` to clear, do the SPI access, and finally set `rn` back to `1`.
Each LED can have 4 mode :
* `00`: Off
* `01`: On
* `10`: Slow blink
* `11`: Fast blink
#### E1 tick channel 0/1 (Read Only, addr `0x04-0x05`)
```text
,-----------------------------------------------------------------------------------------------,
|31|30|29|28|27|26|25|24|23|22|21|20|19|18|17|16|15|14|13|12|11|10| 9| 8| 7| 6| 5| 4| 3| 2| 1| 0|
|-----------------------------------------------------------------------------------------------|
| tx_tick | rx_tick |
'-----------------------------------------------------------------------------------------------'
* [31:16] - tx_tick
* [15: 0] - rx_tick
```
An internal counter is incremented at every bit received/transmitted by the corresponding E1
channel. That counter value is then captured at every USB Start-of-Frame packet and the last
captured value made available here.
#### GPS PPS Time (Read Only, addr `0x06`)
```text
,-----------------------------------------------------------------------------------------------,
|31|30|29|28|27|26|25|24|23|22|21|20|19|18|17|16|15|14|13|12|11|10| 9| 8| 7| 6| 5| 4| 3| 2| 1| 0|
|-----------------------------------------------------------------------------------------------|
| pps_time |
'-----------------------------------------------------------------------------------------------'
* [31:0] - pps_time
```
Time register value (see below) captured at the previous PPS rising edge.
#### Time (Read Only, addr `0x07`)
```text
,-----------------------------------------------------------------------------------------------,
|31|30|29|28|27|26|25|24|23|22|21|20|19|18|17|16|15|14|13|12|11|10| 9| 8| 7| 6| 5| 4| 3| 2| 1| 0|
|-----------------------------------------------------------------------------------------------|
| time |
'-----------------------------------------------------------------------------------------------'
* [31:0] - time
```
32 bit counter incremented at the system clock rate ( 30.72 MHz )
#### PDM (Read/Write, addr `0x08-0x0f`)
This exposes configurable voltages ( DACs ). Some channels are 12 bits, some are 8 bits.
```text
12 bits:
,-----------------------------------------------------------------------------------------------,
|31|30|29|28|27|26|25|24|23|22|21|20|19|18|17|16|15|14|13|12|11|10| 9| 8| 7| 6| 5| 4| 3| 2| 1| 0|
|-----------------------------------------------------------------------------------------------|
|en| / | value |
'-----------------------------------------------------------------------------------------------'
* [31 ] - enable (output tristated if 0)
* [11:0] - value
8 bits:
,-----------------------------------------------------------------------------------------------,
|31|30|29|28|27|26|25|24|23|22|21|20|19|18|17|16|15|14|13|12|11|10| 9| 8| 7| 6| 5| 4| 3| 2| 1| 0|
|-----------------------------------------------------------------------------------------------|
|en| / | value |
'-----------------------------------------------------------------------------------------------'
* [31 ] - enable (output tristated if 0)
* [11:0] - value
```
Channels :
* `0`: Clock tune ( low ) [ 12 bits ]
* `1`: Clock tune ( high ) [ 12 bits ]
* `2`: E1 RX Negative bias [ 8 bits ]
* `3`: E1 RX Positive bias [ 8 bits ]
* `4`: E1 RX Center Tap bias [ 8 bits ]
### `0x8a000000`: I2C
Very simple I2C core.
#### Command (Write Only, addr `0x00`)
```text
,-----------------------------------------------------------------------------------------------,
|31|30|29|28|27|26|25|24|23|22|21|20|19|18|17|16|15|14|13|12|11|10| 9| 8| 7| 6| 5| 4| 3| 2| 1| 0|
|-----------------------------------------------------------------------------------------------|
| / | cmd | / |ak| tx_data |
'-----------------------------------------------------------------------------------------------'
* [13:12] - cmd : Command, see list below
* [8] - ak : TX Ack. Bit to send as ACK for CMD_READ
* [7:0] - tx_data : TX Data. Byte to send for CMD_WRITE
```
Available commands :
* `00: CMD_START`: Issue Start condition
* `01: CMD_STOP`: Issue Stop condition
* `10: CMD_WRITE`: Writes 1 byte and reads the ack bit
* `11: CMD_READ`: Reads 1 byte and write the ack bit
#### Status (Read Only, addr `0x00`)
```text
,-----------------------------------------------------------------------------------------------,
|31|30|29|28|27|26|25|24|23|22|21|20|19|18|17|16|15|14|13|12|11|10| 9| 8| 7| 6| 5| 4| 3| 2| 1| 0|
|-----------------------------------------------------------------------------------------------|
|ry| / / |ak| rx_data |
'-----------------------------------------------------------------------------------------------'
* [32] - ry : Ready bit. If not set, core is busy and rest of data is invalid
* [8] - ak : RX Ack. Bit received as ACK during previous CMD_WRITE
* [7:0] - rx_data : RX Data. Byte read during previous CMD_READ
```

View File

@ -0,0 +1,192 @@
/*
* i2c_master.v
*
* vim: ts=4 sw=4
*
* Copyright (C) 2019-2020 Sylvain Munaut <tnt@246tNt.com>
* SPDX-License-Identifier: CERN-OHL-P-2.0
*/
`default_nettype none
module i2c_master #(
parameter integer DW = 3
)(
// IOs
output reg scl_oe,
output reg sda_oe,
input wire sda_i,
// Control
input wire [7:0] data_in,
input wire ack_in,
input wire [1:0] cmd,
input wire stb,
output wire [7:0] data_out,
output wire ack_out,
output wire ready,
// Clock / Reset
input wire clk,
input wire rst
);
// Commands
localparam [2:0] CMD_START = 3'b00;
localparam [2:0] CMD_STOP = 3'b01;
localparam [2:0] CMD_WRITE = 3'b10;
localparam [2:0] CMD_READ = 3'b11;
// FSM states
localparam
ST_IDLE = 0,
ST_LOWER_SCL = 1,
ST_LOW_CYCLE = 2,
ST_RISE_SCL = 3,
ST_HIGH_CYCLE = 4;
// Signals
// -------
reg [2:0] state;
reg [2:0] state_nxt;
reg [1:0] cmd_cur;
reg [DW:0] cyc_cnt;
wire cyc_now;
reg [3:0] bit_cnt;
wire bit_last;
reg [8:0] data_reg;
// State Machine
// -------------
always @(posedge clk)
if (rst)
state <= ST_IDLE;
else
state <= state_nxt;
always @(*)
begin
// Default is to stay put
state_nxt = state;
// Act depending on current state
case (state)
ST_IDLE:
if (stb)
state_nxt = ST_LOW_CYCLE;
ST_LOW_CYCLE:
if (cyc_now)
state_nxt = ST_RISE_SCL;
ST_RISE_SCL:
if (cyc_now)
state_nxt = ST_HIGH_CYCLE;
ST_HIGH_CYCLE:
if (cyc_now)
state_nxt = (cmd_cur == 2'b01) ? ST_IDLE : ST_LOWER_SCL;
ST_LOWER_SCL:
if (cyc_now)
state_nxt = bit_last ? ST_IDLE : ST_LOW_CYCLE;
endcase
end
// Misc control
// ------------
always @(posedge clk)
if (stb)
cmd_cur <= cmd;
// Baud Rate generator
// -------------------
always @(posedge clk)
if (state == ST_IDLE)
cyc_cnt <= 0;
else
cyc_cnt <= cyc_cnt[DW] ? 0 : (cyc_cnt + 1);
assign cyc_now = cyc_cnt[DW];
// Bit count
// ---------
always @(posedge clk)
if ((state == ST_LOWER_SCL) && cyc_now)
bit_cnt <= bit_cnt + 1;
else if (stb)
case (cmd)
2'b00: bit_cnt <= 4'h8; // START
2'b01: bit_cnt <= 4'h8; // STOP
2'b10: bit_cnt <= 4'h0; // Write
2'b11: bit_cnt <= 4'h0; // Read
default: bit_cnt <= 4'hx;
endcase
assign bit_last = bit_cnt[3];
// Data register
// -------------
always @(posedge clk)
if ((state == ST_HIGH_CYCLE) && cyc_now)
data_reg <= { data_reg[7:0], sda_i };
else if (stb)
// Only handle Write / Read. START & STOP is handled in IO mux
data_reg <= cmd[0] ? { 8'b11111111, ack_in } : { data_in, 1'b1 };
// IO
// --
always @(posedge clk)
if (rst)
scl_oe <= 1'b0;
else if (cyc_now) begin
if (state == ST_LOWER_SCL)
scl_oe <= 1'b1;
else if (state == ST_RISE_SCL)
scl_oe <= 1'b0;
end
always @(posedge clk)
if (rst)
sda_oe <= 1'b0;
else if (cyc_now) begin
if (~cmd_cur[1]) begin
if (state == ST_LOW_CYCLE)
sda_oe <= cmd_cur[0];
else if (state == ST_HIGH_CYCLE)
sda_oe <= ~cmd_cur[0];
end else begin
if (state == ST_LOW_CYCLE)
sda_oe <= ~data_reg[8];
end
end
// User IF
// -------
assign data_out = data_reg[8:1];
assign ack_out = data_reg[0];
assign ready = (state == ST_IDLE);
endmodule

View File

@ -0,0 +1,102 @@
/*
* i2c_master_wb.v
*
* vim: ts=4 sw=4
*
* Wishbone wrapper with optional buffering for i2c_master core
*
* Copyright (C) 2019-2020 Sylvain Munaut <tnt@246tNt.com>
* SPDX-License-Identifier: CERN-OHL-P-2.0
*/
`default_nettype none
module i2c_master_wb #(
parameter integer DW = 3,
parameter integer FIFO_DEPTH = 0
)(
// IOs
output wire scl_oe,
output wire sda_oe,
input wire sda_i,
// Wishbone
output wire [31:0] wb_rdata,
input wire [31:0] wb_wdata,
input wire wb_we,
input wire wb_cyc,
output wire wb_ack,
output wire ready,
// Clock / Reset
input wire clk,
input wire rst
);
// Signals
// -------
wire [7:0] data_in;
wire ack_in;
wire [1:0] cmd;
wire stb;
wire [7:0] data_out;
wire ack_out;
// Core
// ----
i2c_master #(
.DW(DW)
) core_I (
.scl_oe (scl_oe),
.sda_oe (sda_oe),
.sda_i (sda_i),
.data_in (data_in),
.ack_in (ack_in),
.cmd (cmd),
.stb (stb),
.data_out(data_out),
.ack_out (ack_out),
.ready (ready),
.clk (clk),
.rst (rst)
);
// Bus interface (no buffer)
// -------------
if (FIFO_DEPTH == 0) begin
// No buffer
assign wb_rdata = wb_cyc ? { ready, 22'd0, ack_out, data_out } : 32'h00000000;
assign cmd = wb_wdata[13:12];
assign ack_in = wb_wdata[8];
assign data_in = wb_wdata[7:0];
assign stb = wb_cyc & wb_we;
assign wb_ack = wb_cyc;
end
// Bus interface (FIFO)
// -------------
if (FIFO_DEPTH > 0) begin
// Signals
// -------
// FIFOs
// -----
end
endmodule

View File

@ -0,0 +1,106 @@
/*
* led_blinker.v
*
* vim: ts=4 sw=4
*
* Controls E1 led blinking
*
* Copyright (C) 2019-2020 Sylvain Munaut <tnt@246tNt.com>
* SPDX-License-Identifier: CERN-OHL-S-2.0
*/
`default_nettype none
`define SMALL
module led_blinker (
// Requested LED state
input wire [7:0] led_state,
// Shift Register interface
output wire [7:0] sr_val,
output reg sr_go,
input wire sr_rdy,
// Clock / Reset
input wire clk,
input wire rst
);
// ff00 f0f0 cccc aaaa
localparam integer BLINK_SLOW_SPEED = 0;
localparam [15:0] BLINK_SLOW_PATTERN = 16'hf0f0;
localparam integer BLINK_FAST_SPEED = 0;
localparam [15:0] BLINK_FAST_PATTERN = 16'haaaa;
// Signals
// -------
reg [15:0] tick_cnt;
wire tick;
reg [ 9:0] cycle;
wire blink_slow;
wire blink_fast;
reg [ 3:0] led;
// Counter
// -------
// Tick
always @(posedge clk)
`ifdef SMALL
tick_cnt <= (tick_cnt + 1) & (tick ? 16'h0000 : 16'hffff);
`else
tick_cnt <= tick ? 16'h00000 : (tick_cnt+ 1);
`endif
assign tick = tick_cnt[15];
// Cycles
always @(posedge clk)
cycle <= cycle + tick;
// Blink patterns
// --------------
// Base
assign blink_slow = BLINK_SLOW_PATTERN[cycle[9-BLINK_SLOW_SPEED:6-BLINK_SLOW_SPEED]];
assign blink_fast = BLINK_FAST_PATTERN[cycle[9-BLINK_FAST_SPEED:6-BLINK_FAST_SPEED]];
// Per-led
always @(*)
begin : led_state
integer i;
for (i=0; i<4; i=i+1)
led[i] = led_state[2*i+1] ? (led_state[2*i] ? blink_fast : blink_slow) : led_state[2*i];
end
// Request
// -------
// Keep update requests 'pending' for half a cycle
always @(posedge clk or posedge rst)
if (rst)
sr_go <= 1'b0;
else
sr_go <= (sr_go & ~(sr_rdy | tick_cnt[14])) | tick;
assign sr_val = {
led[1],
1'b0,
led[0],
1'b0,
1'b0,
led[2],
1'b0,
led[3]
};
endmodule // led_blinker

337
gateware/icE1usb/rtl/misc.v Normal file
View File

@ -0,0 +1,337 @@
/*
* misc.v
*
* vim: ts=4 sw=4
*
* Misc peripheral functions
*
* Copyright (C) 2019-2020 Sylvain Munaut <tnt@246tNt.com>
* SPDX-License-Identifier: CERN-OHL-S-2.0
*/
`default_nettype none
module misc (
// PDM outputs
output wire [1:0] e1_rx_bias,
output wire clk_tune_hi,
output wire clk_tune_lo,
// GPS
output wire gps_reset_n,
input wire gps_pps,
// GPIO
inout wire [ 2:0] gpio,
// E1 led status
output wire [ 7:0] e1_led_state,
output wire e1_led_run,
input wire e1_led_active,
// Button
input wire btn_val,
input wire btn_stb,
// Ticks
input wire [ 1:0] tick_e1_rx,
input wire [ 1:0] tick_e1_tx,
input wire tick_usb_sof,
// Reset request
output wire rst_req,
// Wishbone
input wire [ 7:0] wb_addr,
output reg [31:0] wb_rdata,
input wire [31:0] wb_wdata,
input wire wb_we,
input wire wb_cyc,
output reg wb_ack,
// Clock / Reset
input wire clk,
input wire rst
);
// Signals
// -------
genvar i;
// Bus
wire bus_clr;
reg bus_we_boot;
reg bus_we_gpio;
reg bus_we_led;
reg [ 1:0] bus_we_pdm_clk;
reg [ 1:0] bus_we_pdm_e1;
// GPIO
reg [3:0] gpio_oe;
reg [3:0] gpio_out;
wire [3:0] gpio_in;
// LED
reg [ 8:0] e1_led;
// PPS sync
wire gps_pps_iob;
wire gps_pps_r;
// Counters
reg [15:0] cnt_e1_rx[0:1];
reg [15:0] cap_e1_rx[0:1];
reg [15:0] cnt_e1_tx[0:1];
reg [15:0] cap_e1_tx[0:1];
reg [31:0] cap_gps;
reg [31:0] cnt_time;
// PDM
reg [12:0] pdm_clk[0:1];
reg [ 8:0] pdm_e1[0:1];
// Boot
reg [1:0] boot_sel;
reg boot_now;
// Bus interface
// -------------
// Ack
always @(posedge clk)
wb_ack <= wb_cyc & ~wb_ack;
assign bus_clr = ~wb_cyc | wb_ack;
// Write enables
always @(posedge clk)
if (bus_clr | ~wb_we) begin
bus_we_boot <= 1'b0;
bus_we_gpio <= 1'b0;
bus_we_led <= 1'b0;
bus_we_pdm_clk[0] <= 1'b0;
bus_we_pdm_clk[1] <= 1'b0;
bus_we_pdm_e1[0] <= 1'b0;
bus_we_pdm_e1[1] <= 1'b0;
end else begin
bus_we_boot <= wb_addr == 4'h0;
bus_we_gpio <= wb_addr == 4'h1;
bus_we_led <= wb_addr == 4'h2;
bus_we_pdm_clk[0] <= wb_addr == 4'h8;
bus_we_pdm_clk[1] <= wb_addr == 4'h9;
bus_we_pdm_e1[0] <= wb_addr == 4'ha;
bus_we_pdm_e1[1] <= wb_addr == 4'hb;
end
// Read mux
always @(posedge clk)
if (bus_clr)
wb_rdata <= 32'h00000000;
else
case (wb_addr[3:0])
4'h1: wb_rdata <= { 12'h000, gpio_in, 4'h0, gpio_oe, 4'h0, gpio_out };
4'h2: wb_rdata <= { 22'h000000, e1_led_active, e1_led_run, e1_led };
4'h4: wb_rdata <= { cap_e1_tx[0], cap_e1_rx[0] };
4'h5: wb_rdata <= { cap_e1_tx[1], cap_e1_rx[1] };
4'h6: wb_rdata <= cap_gps;
4'h7: wb_rdata <= cnt_time;
4'h8: wb_rdata <= { pdm_clk[0][12], 19'h00000, pdm_clk[0][11:0] };
4'h9: wb_rdata <= { pdm_clk[1][12], 19'h00000, pdm_clk[1][11:0] };
4'ha: wb_rdata <= { pdm_e1[0][8], 23'h000000, pdm_e1[0][ 7:0] };
4'hb: wb_rdata <= { pdm_e1[1][8], 23'h000000, pdm_e1[1][ 7:0] };
default: wb_rdata <= 32'hxxxxxxxx;
endcase
// GPIO (incl gps reset)
// ----
// IOB
SB_IO #(
.PIN_TYPE(6'b110100), // Reg in/out/oe
.PULLUP(1'b1),
.IO_STANDARD("SB_LVCMOS")
) gpio_iob_I[3:0] (
.PACKAGE_PIN ({gps_reset_n, gpio}),
.CLOCK_ENABLE (1'b1),
.INPUT_CLK (clk),
.OUTPUT_CLK (clk),
.OUTPUT_ENABLE(gpio_oe),
.D_OUT_0 (gpio_out),
.D_IN_0 (gpio_in)
);
// Bus
always @(posedge clk or posedge rst)
if (rst) begin
gpio_oe <= 4'h0;
gpio_out <= 4'h0;
end else if (bus_we_gpio) begin
gpio_oe <= wb_wdata[11:8];
gpio_out <= wb_wdata[ 3:0];
end
// E1 led status
// -------------
always @(posedge clk or posedge rst)
if (rst)
e1_led <= 9'h00;
else if (bus_we_led)
e1_led <= wb_wdata[8:0];
assign e1_led_state = e1_led[7:0];
assign e1_led_run = e1_led[8];
// PPS input
// ---------
// IO reg
SB_IO #(
.PIN_TYPE(6'b000000), // Reg input, no output
.PULLUP(1'b0),
.IO_STANDARD("SB_LVCMOS")
) btn_iob_I (
.PACKAGE_PIN(gps_pps),
.INPUT_CLK (clk),
.D_IN_0 (gps_pps_iob)
);
// Deglitch
glitch_filter #(
.L(2),
.RST_VAL(1'b0),
.WITH_SYNCHRONIZER(1)
) btn_flt_I (
.in (gps_pps_iob),
.val (),
.rise (gps_pps_r),
.fall (),
.clk (clk),
`ifdef SIM
.rst (rst)
`else
// Don't reset so we let the filter settle before
// the rest of the logic engages
.rst (1'b0)
`endif
);
// Counters
// --------
// E1 ticks
for (i=0; i<2; i=i+1) begin
always @(posedge clk or posedge rst)
if (rst)
cnt_e1_rx[i] <= 16'h0000;
else if (tick_e1_rx[i])
cnt_e1_rx[i] <= cnt_e1_rx[i] + 1;
always @(posedge clk or posedge rst)
if (rst)
cnt_e1_tx[i] <= 16'h0000;
else if (tick_e1_tx[i])
cnt_e1_tx[i] <= cnt_e1_tx[i] + 1;
always @(posedge clk)
if (tick_usb_sof) begin
cap_e1_rx[i] <= cnt_e1_rx[i];
cap_e1_tx[i] <= cnt_e1_tx[i];
end
end
// GPS
always @(posedge clk or posedge rst)
if (rst)
cap_gps <= 32'h00000000;
else if (gps_pps_r)
cap_gps <= cnt_time;
// Time counter
always @(posedge clk)
if (rst)
cnt_time <= 32'h00000000;
else
cnt_time <= cnt_time + 1;
// PDM outputs
// -----------
// Registers
always @(posedge clk or posedge rst)
if (rst) begin
pdm_clk[0] <= 0; // 13'h1800;
pdm_clk[1] <= 0; // 13'h1800;
pdm_e1[0] <= 0; // 9'h190;
pdm_e1[1] <= 0; // 9'h190;
end else begin
if (bus_we_pdm_clk[0]) pdm_clk[0] <= { wb_wdata[31], wb_wdata[11:0] };
if (bus_we_pdm_clk[1]) pdm_clk[1] <= { wb_wdata[31], wb_wdata[11:0] };
if (bus_we_pdm_e1[0]) pdm_e1[0] <= { wb_wdata[31], wb_wdata[ 7:0] };
if (bus_we_pdm_e1[1]) pdm_e1[1] <= { wb_wdata[31], wb_wdata[ 7:0] };
end
// PDM cores
pdm #(
.WIDTH(12),
.PHY("ICE40"),
.DITHER("YES")
) pdm_clk_I[1:0] (
.pdm ({ clk_tune_hi, clk_tune_lo }),
.cfg_val({ pdm_clk[1][11:0], pdm_clk[0][11:0] }),
.cfg_oe ({ pdm_clk[1][12], pdm_clk[0][12] }),
.clk (clk),
.rst (rst)
);
pdm #(
.WIDTH(8),
.PHY("ICE40"),
.DITHER("NO")
) pdm_e1_I[1:0] (
.pdm ({ e1_rx_bias[1], e1_rx_bias[0] }),
.cfg_val({ pdm_e1[1][7:0], pdm_e1[0][7:0] }),
.cfg_oe ({ pdm_e1[1][8], pdm_e1[0][8] }),
.clk (clk),
.rst (rst)
);
// DFU / Reboot
// ------------
always @(posedge clk or posedge rst)
if (rst) begin
boot_now <= 1'b0;
boot_sel <= 2'b00;
end else if (bus_we_boot) begin
boot_now <= wb_wdata[2];
boot_sel <= wb_wdata[1:0];
end
dfu_helper #(
.TIMER_WIDTH(26),
.BTN_MODE(0),
.DFU_MODE(0)
) dfu_I (
.boot_sel(boot_sel),
.boot_now(boot_now),
.btn_pad (btn_val),
.btn_tick(btn_stb),
.btn_val (),
.rst_req (rst_req),
.clk (clk),
.rst (rst)
);
endmodule // misc

View File

@ -0,0 +1,330 @@
/*
* sr_btn_if.v
*
* vim: ts=4 sw=4
*
* Combined SPI + Shift Register + Button input interface
*
* Copyright (C) 2019-2020 Sylvain Munaut <tnt@246tNt.com>
* SPDX-License-Identifier: CERN-OHL-S-2.0
*/
`default_nettype none
`define SMALL
module sr_btn_if #(
parameter integer TICK_LOG2_DIV = 3
)(
// Pads
output wire flash_mosi,
input wire flash_miso,
output wire flash_clk,
output wire flash_cs_n,
inout wire e1_led_rclk,
// SPI module interface
output wire spi_mosi_i,
input wire spi_mosi_o,
input wire spi_mosi_oe,
output wire spi_miso_i,
input wire spi_miso_o,
input wire spi_miso_oe,
output wire spi_clk_i,
input wire spi_clk_o,
input wire spi_clk_oe,
input wire spi_csn_o,
input wire spi_csn_oe,
// SPI muxing req/gnt
input wire spi_req,
output wire spi_gnt,
// Shift Register interface
input wire [7:0] sr_val,
input wire sr_go,
output wire sr_rdy,
// Button status
output reg btn_val,
output reg btn_stb,
// Clock / Reset
input wire clk,
input wire rst
);
// Signals
// -------
// FSM
localparam
ST_IDLE = 0,
ST_SPI = 1,
ST_SHIFT_LO = 2,
ST_SHIFT_HI = 3,
ST_LATCH = 4,
ST_SENSE = 5,
ST_PAUSE = 6;
reg [2:0] state;
reg [2:0] state_nxt;
// Shift Register IO
reg srio_clk_o;
reg srio_dat_o;
reg srio_rclk_o;
reg srio_rclk_oe;
wire srio_rclk_i;
// SPI IO
reg sio_sel;
wire sio_miso_o, sio_miso_oe, sio_miso_i;
wire sio_mosi_o, sio_mosi_oe, sio_mosi_i;
wire sio_clk_o, sio_clk_oe, sio_clk_i;
wire sio_csn_o, sio_csn_oe;
// Input synchronizer
reg [1:0] btn_sync;
// Counters
reg [TICK_LOG2_DIV:0] tick_cnt;
wire tick;
reg [3:0] bit_cnt;
wire bit_cnt_last;
reg [3:0] sense_cnt_in;
reg [3:0] sense_cnt;
wire sense_cnt_last;
// Shift register
reg [7:0] shift_data;
// FSM
// ---
// State register
always @(posedge clk)
if (rst)
state <= ST_IDLE;
else
state <= state_nxt;
// Next-State
always @(*)
begin
// Default
state_nxt = state;
// Change conditions
case (state)
ST_IDLE:
if (sr_go)
state_nxt = ST_SHIFT_LO;
else if (spi_req)
state_nxt = ST_SPI;
ST_SPI:
if (~spi_req)
state_nxt = ST_IDLE;
ST_SHIFT_LO:
if (tick)
state_nxt = ST_SHIFT_HI;
ST_SHIFT_HI:
if (tick)
state_nxt = bit_cnt_last ? ST_LATCH : ST_SHIFT_LO;
ST_LATCH:
if (tick)
state_nxt = ST_SENSE;
ST_SENSE:
if (tick & sense_cnt_last)
state_nxt = ST_PAUSE;
ST_PAUSE:
if (tick)
state_nxt = ST_IDLE;
endcase
end
// IO pads
// -------
// Muxing & Sharing
assign spi_mosi_i = sio_mosi_i;
assign spi_miso_i = sio_miso_i;
assign spi_clk_i = sio_clk_i;
assign sio_mosi_o = sio_sel ? spi_mosi_o : srio_dat_o;
assign sio_mosi_oe = sio_sel ? spi_mosi_oe : 1'b1;
assign sio_miso_o = sio_sel ? spi_miso_o : 1'b0;
assign sio_miso_oe = sio_sel ? spi_miso_oe : 1'b0;
assign sio_clk_o = sio_sel ? spi_clk_o : srio_clk_o;
assign sio_clk_oe = sio_sel ? spi_clk_oe : 1'b1;
assign sio_csn_o = sio_sel ? spi_csn_o : 1'b1;
assign sio_csn_oe = sio_sel ? spi_csn_oe : 1'b1;
// MOSI / MISO / SCK / RCLK
SB_IO #(
.PIN_TYPE(6'b101001),
.PULLUP(1'b1)
) iob_I[3:0] (
.PACKAGE_PIN ({flash_mosi, flash_miso, flash_clk, e1_led_rclk}),
.OUTPUT_ENABLE({sio_mosi_oe, sio_miso_oe, sio_clk_oe, srio_rclk_oe}),
.D_OUT_0 ({sio_mosi_o, sio_miso_o, sio_clk_o, srio_rclk_o}),
.D_IN_0 ({sio_mosi_i, sio_miso_i, sio_clk_i, srio_rclk_i})
);
// Bypass OE for CS_n line
assign flash_cs_n = sio_csn_o;
// SPI grant
// ---------
// Mux select
always @(posedge clk)
sio_sel <= (state_nxt == ST_SPI);
assign spi_gnt = sio_sel;
// Button input synchronizer
// -------------------------
always @(posedge clk)
btn_sync <= { btn_sync[0], srio_rclk_i };
// Control
// -------
// Tick counter
always @(posedge clk)
`ifdef SMALL
tick_cnt <= { (TICK_LOG2_DIV+1){ (~tick & (state != ST_IDLE)) } } & (tick_cnt + 1);
`else
if (state == ST_IDLE)
tick_cnt <= 0;
else
tick_cnt <= tick ? 0 : (tick_cnt + 1);
`endif
assign tick = tick_cnt[TICK_LOG2_DIV];
// Bit counter
always @(posedge clk)
`ifdef SMALL
bit_cnt <= { 4{state != ST_IDLE} } & (bit_cnt + (tick & (state == ST_SHIFT_LO)));
`else
if (state == ST_IDLE)
bit_cnt <= 4'h0;
else if (tick & (state == ST_SHIFT_LO))
bit_cnt <= bit_cnt + 1;
`endif
assign bit_cnt_last = bit_cnt[3];
// Sense counters
`ifdef SMALL
(* keep *) wire state_is_not_latch = (state != ST_LATCH);
`endif
always @(posedge clk)
`ifdef SMALL
begin
sense_cnt <= { 4{state_is_not_latch} } & (sense_cnt + tick);
sense_cnt_in <= { 4{state_is_not_latch} } & (sense_cnt_in + (tick & btn_sync[1]));
end
`else
if (state == ST_LATCH) begin
sense_cnt <= 0;
sense_cnt_in <= 0;
end else if (tick) begin
sense_cnt <= sense_cnt + 1;
sense_cnt_in <= sense_cnt_in + btn_sync[1];
end
`endif
assign sense_cnt_last = sense_cnt[3];
// Decision
always @(posedge clk)
`ifdef SMALL
btn_val <= ((state == ST_PAUSE) & (sense_cnt_in[3:2] == 2'b00)) | ((state != ST_PAUSE) & btn_val);
`else
if (state == ST_PAUSE)
btn_val <= (sense_cnt_in[3:2] == 2'b00);
`endif
always @(posedge clk)
btn_stb <= (state == ST_PAUSE) & tick;
// Data shift register
`ifdef SMALL
wire [7:0] m = { 8{ sr_go & sr_rdy } };
wire [7:0] shift_data_nxt = (sr_val & m) | ({ shift_data[6:0], 1'b0 } & ~m);
wire shift_ce = (sr_go & sr_rdy) | (tick & (state == ST_SHIFT_HI));
always @(posedge clk)
if (shift_ce)
shift_data <= shift_data_nxt;
`else
always @(posedge clk)
if (sr_go & sr_rdy)
shift_data <= sr_val;
else if (tick & (state == ST_SHIFT_HI))
shift_data <= { shift_data[6:0], 1'b0 };
`endif
// IO control
always @(posedge clk)
begin
// Defaults
srio_clk_o <= 1'b0;
srio_dat_o <= 1'b0;
srio_rclk_o <= 1'b0;
srio_rclk_oe <= 1'b1;
// Depends on state
case (state)
ST_SHIFT_LO: begin
srio_dat_o <= shift_data[7];
srio_clk_o <= 1'b0;
end
ST_SHIFT_HI: begin
srio_dat_o <= shift_data[7];
srio_clk_o <= 1'b1;
end
ST_LATCH: begin
srio_rclk_o <= 1'b1;
end
ST_SENSE: begin
srio_rclk_o <= 1'b1;
srio_rclk_oe <= 1'b0;
end
ST_PAUSE: begin
srio_rclk_o <= 1'b0;
srio_rclk_oe <= 1'b0;
end
endcase
end
// External status
assign sr_rdy = (state == ST_IDLE);
endmodule // sr_btn_if

View File

@ -0,0 +1,100 @@
/*
* sysmgr.v
*
* vim: ts=4 sw=4
*
* System Clock / Reset generation
*
* Copyright (C) 2019-2020 Sylvain Munaut <tnt@246tNt.com>
* SPDX-License-Identifier: CERN-OHL-S-2.0
*/
`default_nettype none
module sysmgr (
input wire clk_in,
input wire rst_in,
output wire clk_sys,
output wire rst_sys,
output wire clk_48m,
output wire rst_48m
);
// Signals
wire pll_lock;
wire pll_reset_n;
wire clk_30m72_i;
wire rst_30m72_i;
wire clk_48m_i;
reg rst_48m_i;
reg [3:0] rst_cnt;
// Global input buffer for 30.72 MHz clock
SB_GB_IO #(
.PIN_TYPE(6'b000001),
) gb_in (
.PACKAGE_PIN(clk_in),
.GLOBAL_BUFFER_OUTPUT(clk_30m72_i),
);
// PLL instance
SB_PLL40_CORE #(
.DIVR(4'b0000),
.DIVF(7'b0011000),
.DIVQ(3'b100),
.FILTER_RANGE(3'b011),
.FEEDBACK_PATH("SIMPLE"),
.DELAY_ADJUSTMENT_MODE_FEEDBACK("FIXED"),
.FDA_FEEDBACK(4'b0000),
.SHIFTREG_DIV_MODE(2'b00),
.PLLOUT_SELECT("GENCLK"),
.ENABLE_ICEGATE(1'b0),
) pll_I (
.REFERENCECLK(clk_30m72_i),
.PLLOUTCORE(),
.PLLOUTGLOBAL(clk_48m_i),
.EXTFEEDBACK(1'b0),
.DYNAMICDELAY(8'h00),
.RESETB(pll_reset_n),
.BYPASS(1'b0),
.LATCHINPUTVALUE(1'b0),
.LOCK(pll_lock),
.SDI(1'b0),
.SDO(),
.SCLK(1'b0)
);
assign clk_sys = clk_30m72_i;
assign clk_48m = clk_48m_i;
// PLL reset generation
assign pll_reset_n = ~rst_in;
// Logic reset generation
always @(posedge clk_30m72_i or negedge pll_lock)
if (!pll_lock)
rst_cnt <= 4'h0;
else if (~rst_cnt[3])
rst_cnt <= rst_cnt + 1;
assign rst_30m72_i = ~rst_cnt[3];
always @(posedge clk_48m or posedge rst_30m72_i)
if (rst_30m72_i)
rst_48m_i <= 1'b1;
else
rst_48m_i <= 1'b0;
SB_GB rst_sys_gbuf_I (
.USER_SIGNAL_TO_GLOBAL_BUFFER(rst_30m72_i),
.GLOBAL_BUFFER_OUTPUT(rst_sys)
);
SB_GB rst_48m_gbuf_I (
.USER_SIGNAL_TO_GLOBAL_BUFFER(rst_48m_i),
.GLOBAL_BUFFER_OUTPUT(rst_48m)
);
endmodule // sysmgr

388
gateware/icE1usb/rtl/top.v Normal file
View File

@ -0,0 +1,388 @@
/*
* top.v
*
* vim: ts=4 sw=4
*
* Top-level for the icE1usb production boards
*
* Copyright (C) 2019-2020 Sylvain Munaut <tnt@246tNt.com>
* SPDX-License-Identifier: CERN-OHL-S-2.0
*/
`default_nettype none
module top (
// E1 PHY
input wire e1A_rx_hi_p,
// input wire e1A_rx_hi_n,
input wire e1A_rx_lo_p,
// input wire e1A_rx_lo_n,
output wire e1A_tx_hi,
output wire e1A_tx_lo,
input wire e1B_rx_hi_p,
// input wire e1B_rx_hi_n,
input wire e1B_rx_lo_p,
// input wire e1B_rx_lo_n,
output wire e1B_tx_hi,
output wire e1B_tx_lo,
output wire [1:0] e1_rx_bias,
// USB
inout wire usb_dp,
inout wire usb_dn,
output wire usb_pu,
// Flash
inout wire flash_mosi,
inout wire flash_miso,
inout wire flash_clk,
inout wire flash_cs_n,
// LED Shift register + Button input
inout wire e1_led_rclk,
// GPS
output wire gps_reset_n,
input wire gps_rx,
output wire gps_tx,
input wire gps_pps,
// I2C
inout wire i2c_sda,
inout wire i2c_scl,
// GPIOs
inout wire [2:0] gpio,
// Clock (30.72 MHz)
input wire clk_in,
output wire clk_tune_hi,
output wire clk_tune_lo,
// Debug UART
input wire dbg_rx,
output wire dbg_tx,
// RGB LEDs
output wire [2:0] rgb
);
localparam integer WB_N = 3;
genvar i;
// Signals
// -------
// Flash SPI internal signals
wire flash_mosi_i, flash_miso_i, flash_clk_i;
wire flash_mosi_o, flash_miso_o, flash_clk_o;
wire flash_mosi_oe, flash_miso_oe, flash_clk_oe;
wire flash_csn_o;
// Peripheral wishbone
wire [15:0] wb_addr;
wire [31:0] wb_rdata [0:WB_N-1];
wire [31:0] wb_wdata;
wire [ 3:0] wb_wmsk;
wire wb_we;
wire [WB_N-1:0] wb_cyc;
wire [WB_N-1:0] wb_ack;
wire [(WB_N*32)-1:0] wb_rdata_flat;
// Ticks
wire [1:0] tick_e1_rx;
wire [1:0] tick_e1_tx;
wire tick_usb_sof;
// I2C
wire i2c_scl_oe;
wire i2c_sda_oe;
wire i2c_sda_i;
// Led & Button
wire [7:0] e1_led_state;
wire e1_led_run;
wire e1_led_active;
wire spi_req;
wire spi_gnt;
wire [7:0] sr_val;
wire sr_go;
wire sr_rdy;
wire btn_val;
wire btn_stb;
// Clocks / Reset
wire rst_req;
wire clk_sys;
wire rst_sys;
wire clk_48m;
wire rst_48m;
// SoC base
// --------
// Instance
soc_base #(
.WB_N(WB_N),
.E1_N(2),
.E1_UNIT_HAS_RX(2'b01),
.E1_UNIT_HAS_TX(2'b01),
.E1_LIU(0)
) soc_I (
.e1_rx_hi_p ({e1B_rx_hi_p, e1A_rx_hi_p}),
// .e1_rx_hi_n ({e1B_rx_hi_n, e1A_rx_hi_n}),
.e1_rx_lo_p ({e1B_rx_lo_p, e1A_rx_lo_p}),
// .e1_rx_lo_n ({e1B_rx_lo_n, e1A_rx_lo_n}),
.e1_tx_hi ({e1B_tx_hi, e1A_tx_hi }),
.e1_tx_lo ({e1B_tx_lo, e1A_tx_lo }),
.e1_rx_data (),
.e1_rx_clk (),
.e1_tx_data (),
.e1_tx_clk (),
.usb_dp (usb_dp),
.usb_dn (usb_dn),
.usb_pu (usb_pu),
.flash_mosi_i (flash_mosi_i),
.flash_mosi_o (flash_mosi_o),
.flash_mosi_oe(flash_mosi_oe),
.flash_miso_i (flash_miso_i),
.flash_miso_o (flash_miso_o),
.flash_miso_oe(flash_miso_oe),
.flash_clk_i (flash_clk_i),
.flash_clk_o (flash_clk_o),
.flash_clk_oe (flash_clk_oe),
.flash_csn_o (flash_csn_o),
.dbg_rx (dbg_rx),
.dbg_tx (dbg_tx),
.rgb (rgb),
.wb_m_addr (wb_addr),
.wb_m_rdata (wb_rdata_flat),
.wb_m_wdata (wb_wdata),
.wb_m_wmsk (wb_wmsk),
.wb_m_we (wb_we),
.wb_m_cyc (wb_cyc),
.wb_m_ack (wb_ack),
.tick_e1_rx (tick_e1_rx),
.tick_e1_tx (tick_e1_tx),
.tick_usb_sof (tick_usb_sof),
.clk_sys (clk_sys),
.rst_sys (rst_sys),
.clk_48m (clk_48m),
.rst_48m (rst_48m)
);
// WB read data flattening
for (i=0; i<WB_N; i=i+1)
assign wb_rdata_flat[i*32+:32] = wb_rdata[i];
// Dummy channel
// -------------
wire [1:0] e1_dummy;
SB_IO #(
.PIN_TYPE(6'b000000),
.PULLUP(1'b0),
.NEG_TRIGGER(1'b0),
.IO_STANDARD("SB_LVDS_INPUT")
) e1_dummy_rx_I[1:0] (
.PACKAGE_PIN({e1B_rx_hi_p, e1B_rx_lo_p}),
.LATCH_INPUT_VALUE(1'b0),
.CLOCK_ENABLE(1'b1),
.INPUT_CLK(clk_sys),
.OUTPUT_CLK(1'b0),
.OUTPUT_ENABLE(1'b0),
.D_OUT_0(1'b0),
.D_OUT_1(1'b0),
.D_IN_0(e1_dummy),
.D_IN_1()
);
SB_IO #(
.PIN_TYPE(6'b010100),
.PULLUP(1'b0),
.NEG_TRIGGER(1'b0),
.IO_STANDARD("SB_LVCMOS")
) e1_dummy_tx_I[1:0] (
.PACKAGE_PIN({e1B_tx_hi, e1B_tx_lo}),
.LATCH_INPUT_VALUE(1'b0),
.CLOCK_ENABLE(1'b1),
.INPUT_CLK(1'b0),
.OUTPUT_CLK(clk_sys),
.OUTPUT_ENABLE(1'b0),
.D_OUT_0(e1_dummy),
.D_OUT_1(1'b0),
.D_IN_0(),
.D_IN_1()
);
// Misc [0]
// ----
misc misc_I (
.e1_rx_bias (e1_rx_bias),
.clk_tune_hi (clk_tune_hi),
.clk_tune_lo (clk_tune_lo),
.gps_reset_n (gps_reset_n),
.gps_pps (gps_pps),
.gpio (gpio),
.e1_led_state (e1_led_state),
.e1_led_run (e1_led_run),
.e1_led_active (e1_led_active),
.btn_val (btn_val),
.btn_stb (btn_stb),
.tick_e1_rx (tick_e1_rx),
.tick_e1_tx (tick_e1_tx),
.tick_usb_sof (tick_usb_sof),
.rst_req (rst_req),
.wb_addr (wb_addr[7:0]),
.wb_rdata (wb_rdata[0]),
.wb_wdata (wb_wdata),
.wb_we (wb_we),
.wb_cyc (wb_cyc[0]),
.wb_ack (wb_ack[0]),
.clk (clk_sys),
.rst (rst_sys)
);
// GPS UART [1]
// --------
uart_wb #(
.DIV_WIDTH(12),
.DW(32)
) gps_uart_I (
.uart_tx (gps_tx),
.uart_rx (gps_rx),
.wb_addr (wb_addr[1:0]),
.wb_rdata (wb_rdata[1]),
.wb_wdata (wb_wdata),
.wb_we (wb_we),
.wb_cyc (wb_cyc[1]),
.wb_ack (wb_ack[1]),
.clk (clk_sys),
.rst (rst_sys)
);
// I2C [2]
// ---
// Controller
i2c_master_wb #(
.DW(3),
.FIFO_DEPTH(0)
) i2c_I (
.scl_oe (i2c_scl_oe),
.sda_oe (i2c_sda_oe),
.sda_i (i2c_sda_i),
.wb_rdata(wb_rdata[2]),
.wb_wdata(wb_wdata),
.wb_we (wb_we),
.wb_cyc (wb_cyc[2]),
.wb_ack (wb_ack[2]),
.ready (),
.clk (clk_sys),
.rst (rst_sys)
);
// IOBs
SB_IO #(
.PIN_TYPE(6'b110101),
.PULLUP(1'b1),
.IO_STANDARD("SB_LVCMOS")
) i2c_scl_iob_I (
.PACKAGE_PIN (i2c_scl),
.OUTPUT_CLK (clk_sys),
.OUTPUT_ENABLE(i2c_scl_oe),
.D_OUT_0 (1'b0)
);
SB_IO #(
.PIN_TYPE(6'b110100),
.PULLUP(1'b1),
.IO_STANDARD("SB_LVCMOS")
) i2c_sda_iob_I (
.PACKAGE_PIN (i2c_sda),
.INPUT_CLK (clk_sys),
.OUTPUT_CLK (clk_sys),
.OUTPUT_ENABLE(i2c_sda_oe),
.D_OUT_0 (1'b0),
.D_IN_0 (i2c_sda_i)
);
// E1 LEDs & Button
// ----------------
// Blink pattern generator
led_blinker blinker_I (
.led_state(e1_led_state),
.sr_val (sr_val),
.sr_go (sr_go),
.sr_rdy (sr_rdy),
.clk (clk_sys),
.rst (rst_sys)
);
// Interface
sr_btn_if #(
.TICK_LOG2_DIV(3)
) spi_mux_I (
.flash_mosi (flash_mosi),
.flash_miso (flash_miso),
.flash_clk (flash_clk),
.flash_cs_n (flash_cs_n),
.e1_led_rclk (e1_led_rclk),
.spi_mosi_i (flash_mosi_i),
.spi_mosi_o (flash_mosi_o),
.spi_mosi_oe (flash_mosi_oe),
.spi_miso_i (flash_miso_i),
.spi_miso_o (flash_miso_o),
.spi_miso_oe (flash_miso_oe),
.spi_clk_i (flash_clk_i),
.spi_clk_o (flash_clk_o),
.spi_clk_oe (flash_clk_oe),
.spi_csn_o (flash_csn_o),
.spi_csn_oe (1'b1),
.spi_req (spi_req),
.spi_gnt (spi_gnt),
.sr_val (sr_val),
.sr_go (sr_go),
.sr_rdy (sr_rdy),
.btn_val (btn_val),
.btn_stb (btn_stb),
.clk (clk_sys),
.rst (rst_sys)
);
assign spi_req = ~e1_led_run;
assign e1_led_active = ~spi_gnt;
// Clock / Reset
// -------------
sysmgr sys_mgr_I (
.clk_in (clk_in),
.rst_in (rst_req),
.clk_sys(clk_sys),
.rst_sys(rst_sys),
.clk_48m(clk_48m),
.rst_48m(rst_48m)
);
endmodule // top

View File

@ -0,0 +1,117 @@
/*
* i2c_master_tb.v
*
* vim: ts=4 sw=4
*
* Copyright (C) 2019-2020 Sylvain Munaut <tnt@246tNt.com>
* SPDX-License-Identifier: CERN-OHL-P-2.0
*/
`default_nettype none
`timescale 1ns / 100ps
module i2c_master_tb;
// Signals
// -------
reg rst = 1'b1;
reg clk = 1'b0;
// Test bench
// ----------
// Setup recording
initial begin
$dumpfile("i2c_master_tb.vcd");
$dumpvars(0,i2c_master_tb);
end
// Reset pulse
initial begin
# 200 rst = 0;
# 1000000 $finish;
end
// Clocks
always #10 clk = !clk;
// DUT
// ---
wire scl_oe;
wire sda_oe;
wire sda_i;
reg [7:0] data_in;
reg ack_in;
reg [1:0] cmd;
reg stb;
wire [7:0] data_out;
wire ack_out;
wire ready;
i2c_master #(
.DW(3)
) dut_I (
.scl_oe(scl_oe),
.sda_oe(sda_oe),
.sda_i(sda_i),
.data_in(data_in),
.ack_in(ack_in),
.cmd(cmd),
.stb(stb),
.data_out(data_out),
.ack_out(ack_out),
.ready(ready),
.clk(clk),
.rst(rst)
);
// Stimulus
// --------
assign sda_i = 1'b0;
task i2c_cmd;
input [1:0] a_cmd;
input [7:0] a_data;
input a_ack;
begin
cmd <= a_cmd;
data_in <= a_data;
ack_in <= a_ack;
stb <= 1'b1;
@(posedge clk);
stb <= 1'b0;
@(posedge clk);
wait (ready == 1'b1);
@(posedge clk);
end
endtask
initial begin
// Reset
data_in <= 8'h00;
ack_in <= 1'b0;
cmd <= 2'b00;
stb <= 1'b0;
wait (rst == 1'b0);
wait (ready == 1'b1);
@(posedge clk);
// Issue commands
i2c_cmd(2'b00, 8'h00, 1'b0);
i2c_cmd(2'b10, 8'ha5, 1'b0);
i2c_cmd(2'b11, 8'h00, 1'b0);
i2c_cmd(2'b01, 8'h00, 1'b0);
end
endmodule