123456789101112131415161718192021222324252627282930313233343536373839404142434445464748495051525354555657585960616263646566676869707172737475767778798081828384858687888990919293949596979899100101102103104105106107108109110111112113114115116117118119120121122123124125126127128129130131132133134135136137138139140141142143144145146147148149150151152153154155156157158159160161162163164165166167168169170171172173174175176177178179180181182183184185186187188189190191192193194195196197198199200201202203204205206207208209210211212213214215216217218219220221222223224225226227228229230231232233234235236237238239240241242243244245246247248249250251252253254255256257258259260261262263264265266267268269270271272273274275276277278279280281282283284285286287288289290291292293294295296297298299300301302303304305306307308309310311312313314315316317318319320321322323324325326327328329330331332333334335336337338339340341342343344345346347348349350351352353354355356357358359360361362363364365366367368369370371372373374375376377378379380381382383384385386387388389390391392393394395396397398399400401402403404405406407408409410411412413414415416417418419420421422423424425426427428429430431432433434435436437438439440441442443444445446447448449450451452453454455456457458459460461462463464465466467468469470471472473474475476477478479480481482483484485486487488489490491492493494495496497498499500501502503504505506507508509510511512513514515516517518519520521522523524525526527528529530531532533534535536537538539540541542543544545546547548549550551552553554555556557558559560561562563564565566567568569570571572573574575576577578579580581582583584585586587588589590591592593594595596597598599600601602603604605606607608609610611612613614615616617618619620621622623624625626627628629630631632633634635636637638639640641642643644645646647648649650651652653654655656657658659660661662663664665666667668669670671672673674675676677678679680681682683684685686687688689690691692693694695696697698699700701702703704705706707708709710711712713714715716717718719720721722723724725726727728729730731732733734735736737738739740741742743744745746747748749750751752753754755756757758759760761762763764765766767768769770771772773774775776777778779780781782783784785786787788789790791792793794795796797798799800801802803804805806807808809810811812813814815816817818819820821822823824825826827828829830831832833834835836837838839840841842843844845846847848849850851852853854855856857858859860861862863864865866867868869870871872873874875876877878879880881882883884885886887888889890891892893894895896897898899900901902903904905906907908909910911912913914915916917918919920921922923924925926927928929930931932933934935936937938939940941942943944945946947948949 |
- //
- // Top level module for the FPGA on the MAX80 board by
- // Per Mårtensson and H. Peter Anvin
- //
- // This is for MAX80 as target on the ABC-bus.
- //
- // Sharing JTAG pins (via JTAGEN)
- `undef SHARED_JTAG
- module max80
- #(parameter logic [6:1] x_mosfet,
- parameter logic [7:0] fpga_ver)
- (
- // Clock oscillator
- input master_clk, // 336 MHz from PLL2
- input slow_clk, // ~12 MHz clock from PLL2
- input master_pll_locked, // PLL2 is locked, master_clk is good
- output reset_plls, // Reset all PLLs including PLL2
- input board_id, // This better match the firmware
- // ABC-bus
- inout abc_clk, // ABC-bus 3 MHz clock
- inout [15:0] abc_a, // ABC address bus
- inout [7:0] abc_d, // ABC data bus
- output abc_d_oe, // Data bus output enable
- inout abc_rst_n, // ABC bus reset strobe
- inout abc_cs_n, // ABC card select strobe
- inout [4:0] abc_out_n, // OUT, C1-C4 strobe
- inout [1:0] abc_inp_n, // INP, STATUS strobe
- inout abc_xmemfl_n, // Memory read strobe
- inout abc_xmemw800_n, // Memory write strobe (ABC800)
- inout abc_xmemw80_n, // Memory write strobe (ABC80)
- inout abc_xinpstb_n, // I/O read strobe (ABC800)
- inout abc_xoutpstb_n, // I/O write strobe (ABC80)
- // The following are inverted versus the bus IF
- // the corresponding MOSFETs are installed
- inout abc_rdy_x, // RDY = WAIT#
- inout abc_resin_x, // System reset request
- inout abc_int80_x, // System INT request (ABC80)
- inout abc_int800_x, // System INT request (ABC800)
- inout abc_nmi_x, // System NMI request (ABC800)
- inout abc_xm_x, // System memory override (ABC800)
- // Host/device control
- output abc_host, // 1 = host, 0 = target
- // ABC-bus extension header
- // (Note: cannot use an array here because HC and HH are
- // input only.)
- inout exth_ha,
- inout exth_hb,
- input exth_hc,
- inout exth_hd,
- inout exth_he,
- inout exth_hf,
- inout exth_hg,
- input exth_hh,
- // SDRAM bus
- output sr_clk,
- output [1:0] sr_ba, // Bank address
- output [12:0] sr_a, // Address within bank
- inout [15:0] sr_dq, // Also known as D or IO
- output [1:0] sr_dqm, // DQML and DQMH
- output sr_cs_n,
- output sr_we_n,
- output sr_cas_n,
- output sr_ras_n,
- // SD card
- input sd_cd_n,
- output sd_cs_n,
- output sd_clk,
- output sd_di,
- input sd_do,
- // Serial console (naming is FPGA as DCE)
- input tty_txd,
- output tty_rxd,
- input tty_rts,
- output tty_cts,
- input tty_dtr,
- // SPI flash memory (also configuration)
- output flash_cs_n,
- output flash_sck,
- inout [1:0] flash_io,
- // SPI bus (connected to ESP32 so can be bidirectional)
- inout spi_clk, // ESP32 IO12
- inout [1:0] spi_io, // ESP32 IO13,IO11
- inout spi_cs_esp_n, // ESP32 IO10
- inout spi_cs_flash_n, // ESP32 IO01
- // Other ESP32 connections
- inout esp_io0, // ESP32 IO00
- inout esp_int, // ESP32 IO09
- // I2C bus (RTC and external)
- inout i2c_scl,
- inout i2c_sda,
- input rtc_32khz,
- input rtc_int_n,
- // LEDs
- output [2:0] led,
- // USB
- inout usb_dp,
- inout usb_dn,
- output usb_pu,
- input usb_rx,
- input usb_rx_ok,
- // HDMI
- output [2:0] hdmi_d,
- output hdmi_clk,
- inout hdmi_scl,
- inout hdmi_sda,
- inout hdmi_hpd,
- // Unconnected pins with pullups, used for randomness
- inout [2:0] rngio,
- // Various clocks available to the top level as well as internally
- output sdram_clk, // 168 MHz SDRAM clock
- output sys_clk, // 84 MHz System clock
- output flash_clk, // 134 MHz Serial flash ROM clock
- output usb_clk, // 48 MHz USB clock
- output vid_clk, // 56 MHz Video pixel clock
- output vid_hdmiclk // 280 MHz HDMI serializer clock = vid_clk x 5
- );
- // -----------------------------------------------------------------------
- // PLLs and reset
- // -----------------------------------------------------------------------
- reg rst_n = 1'b0; // Internal system reset
- reg hard_rst_n = 1'b0; // Strict POR reset only
- wire reconfig_rst; // Reconfigure FPGA
- assign reset_plls = 1'b0;
- tri1 [4:1] pll_locked;
- assign pll_locked[2] = master_pll_locked;
- fpgarst fpgarst (
- .rst_n ( master_pll_locked ),
- .clk ( slow_clk ),
- .reconfig ( reconfig_rst )
- );
- //
- // Clocks.
- //
- // All clocks are derived from a common oscillator connected to an
- // input clock pin, which is a dedicated clock pin feeding into
- // hardware PLL2 and PLL4. The SDRAM clock output is a dedicated
- // clock out pin from PLL3.
- //
- // The input frequency is not consistent across board revisions,
- // so PLL2 is configured to produce a common master clock (336 MHz)
- // in the appropriate top level file.
- //
- // The following sets of clocks are closely tied and expected to
- // be synchronous, and therefore should come from the same PLL each;
- // furthermore, the design strictly assumes the ratios specified.
- //
- // sdram_clk, sys_clk - 2:1 ratio
- // vid_hdmiclk, vid_clk - 5:1 ratio
- //
- pll3 pll3 (
- .areset ( ~pll_locked[2] ),
- .locked ( pll_locked[3] ),
- .inclk0 ( master_clk ),
- .c0 ( sr_clk ), // Output to clock pin (phase shift)
- .c1 ( sdram_clk ), // Internal logic/buffer data clock
- .c2 ( sys_clk ),
- .c3 ( flash_clk ),
- .c4 ( usb_clk )
- );
- pll4 pll4 (
- .areset ( ~pll_locked[2] ),
- .locked ( pll_locked[4] ),
- .inclk0 ( master_clk ),
- .c0 ( vid_hdmiclk ),
- .c1 ( vid_clk )
- );
- wire all_plls_locked = &pll_locked;
- //
- // sys_clk pulse generation of various powers of two; allows us to
- // reuse the same counter for a lot of things that require periodic
- // timing events without strong requirements on the specific timing.
- // The first strobe is asserted 2^n cycles after rst_n goes high.
- //
- // The same counter is used to hold rst_n and hard_rst_n low for
- // 2^reset_pow2 cycles.
- //
- // XXX: reuse this counter for the CPU cycle counter.
- //
- localparam reset_pow2 = 12;
- reg [31:0] sys_clk_ctr;
- reg [31:0] sys_clk_ctr_q;
- reg [31:1] sys_clk_stb;
- // 3 types of reset: system, hard, and reconfig
- wire [3:1] cpu_reset_cmd; // CPU-originated reset command
- reg [3:1] cpu_reset_cmd_q[0:1];
- wire [3:1] aux_reset_cmd; // Other reset sources
- reg [3:1] reset_cmd_q = 3'b0;
- assign reconfig_rst = reset_cmd_q[3];
- always @(negedge all_plls_locked or posedge sys_clk)
- if (~all_plls_locked)
- begin
- hard_rst_n <= 1'b0;
- rst_n <= 1'b0;
- reset_cmd_q[2:1] <= 3'b0;
- cpu_reset_cmd_q[0] <= 3'b0;
- cpu_reset_cmd_q[1] <= 3'b0;
- sys_clk_ctr <= (-'sb1) << reset_pow2;
- sys_clk_ctr_q <= 'b0;
- sys_clk_stb <= 'b0;
- end
- else
- begin
- cpu_reset_cmd_q[0] <= cpu_reset_cmd;
- cpu_reset_cmd_q[1] <= cpu_reset_cmd_q[0];
- reset_cmd_q <= (cpu_reset_cmd_q[0] & ~cpu_reset_cmd_q[1]) |
- aux_reset_cmd;
- // Reconfig reset is sticky until FPGA reloaded...
- reset_cmd_q[3] <= reset_cmd_q[3] | cpu_reset_cmd_q[0][3] |
- aux_reset_cmd[3];
- if (|reset_cmd_q)
- begin
- // Soft or hard reset
- sys_clk_ctr <= (-'sb1) << reset_pow2;
- sys_clk_ctr_q <= 1'b0;
- sys_clk_stb <= 1'b0;
- rst_n <= 1'b0;
- hard_rst_n <= hard_rst_n & ~|reset_cmd_q[3:2];
- end
- else
- begin
- sys_clk_ctr <= sys_clk_ctr + 1'b1;
- sys_clk_ctr_q <= ~rst_n ? 'b0 : sys_clk_ctr;
- sys_clk_stb <= ~sys_clk_ctr & sys_clk_ctr_q;
- rst_n <= rst_n | ~sys_clk_ctr[reset_pow2];
- hard_rst_n <= hard_rst_n | ~sys_clk_ctr[reset_pow2];
- end
- end
- // Reset in the video clock domain
- reg vid_rst_n;
- always @(negedge all_plls_locked or posedge vid_clk)
- if (~all_plls_locked)
- vid_rst_n <= 1'b0;
- else
- vid_rst_n <= rst_n;
- // HDMI video interface
- video video (
- .rst_n ( vid_rst_n ),
- .vid_clk ( vid_clk ),
- .vid_hdmiclk ( vid_hdmiclk ),
- .hdmi_d ( hdmi_d ),
- .hdmi_clk ( hdmi_clk ),
- .hdmi_scl ( hdmi_scl ),
- .hdmi_hpd ( hdmi_hpd )
- );
- //
- // Internal CPU bus
- //
- wire cpu_mem_valid;
- wire cpu_mem_ready;
- wire cpu_mem_instr;
- wire [ 3:0] cpu_mem_wstrb;
- wire [31:0] cpu_mem_addr;
- wire [31:0] cpu_mem_wdata;
- reg [31:0] cpu_mem_rdata;
- wire cpu_la_read;
- wire cpu_la_write;
- wire [31:0] cpu_la_addr;
- wire [31:0] cpu_la_wdata;
- wire [ 3:0] cpu_la_wstrb;
- // cpu_mem_valid by address quadrant, using a bit of lookahead
- // decoding for speed.
- reg [3:0] mem_quad;
- always @(negedge rst_n or posedge sys_clk)
- if (~rst_n)
- mem_quad <= 4'b0;
- else if (cpu_mem_valid)
- mem_quad <= 1'b1 << cpu_mem_addr[31:30];
- else
- mem_quad <= 1'b1 << cpu_la_addr[31:30];
- wire [3:0] cpu_mem_quad = cpu_mem_valid ? mem_quad : 4'b0;
- // I/O device map from iodevs.conf
- wire iodev_mem_valid = cpu_mem_quad[3];
- `include "iodevs.vh"
- //
- // SDRAM
- //
- localparam dram_port_count = 4;
- dram_bus sr_bus[1:dram_port_count] ( );
- // ABC interface
- wire [24:0] abc_sr_addr;
- wire [ 7:0] abc_sr_rd;
- wire abc_sr_valid;
- wire abc_sr_ready;
- wire [ 7:0] abc_sr_wd;
- wire abc_sr_wstrb;
- dram_port #(8)
- abc_dram_port (
- .bus ( sr_bus[1] ),
- .prio ( 2'd3 ),
- .addr ( abc_sr_addr ),
- .rd ( abc_sr_rd ),
- .valid ( abc_sr_valid ),
- .ready ( abc_sr_ready ),
- .wd ( abc_sr_wd ),
- .wstrb ( abc_sr_wstrb )
- );
- // CPU interface
- wire sdram_valid = cpu_mem_quad[1];
- wire [31:0] sdram_mem_rdata;
- wire sdram_ready;
- reg sdram_ready_q;
- reg sdram_mem_ready;
- //
- // Retard sdram_ready by one sys_clk (multicycle path for the data,
- // see max80.sdc)
- //
- // Note that if the CPU leaves valid asserted the CPU cycle after
- // receiving ready, it is the beginning of another request. The
- // sdram core expects valid to be strobed, so deassert valid
- // to the sdram core while asserting ready to the CPU.
- //
- always @(posedge sys_clk)
- begin
- sdram_mem_ready <= sdram_ready & sdram_valid;
- end
- dram_port #(32)
- cpu_dram_port (
- .bus ( sr_bus[4] ),
- .prio ( 2'd1 ),
- .addr ( cpu_mem_addr[24:0] ),
- .rd ( sdram_mem_rdata ),
- .valid ( sdram_valid & ~sdram_mem_ready ),
- .ready ( sdram_ready ),
- .wd ( cpu_mem_wdata ),
- .wstrb ( cpu_mem_wstrb )
- );
- // Romcopy interface
- wire [15:0] sdram_rom_wd;
- wire [24:1] sdram_rom_waddr;
- wire [ 1:0] sdram_rom_wrq;
- wire sdram_rom_wacc;
- sdram #(.port1_count(dram_port_count))
- sdram (
- .rst_n ( rst_n ),
- .clk ( sdram_clk ), // Internal memory clock
- .init_tmr ( sys_clk_stb[14] ), // > 100 μs (tP) after reset
- .rfsh_tmr ( sys_clk_stb[8] ), // < 3.9 μs (tREFI/2)
- .sr_cs_n ( sr_cs_n ),
- .sr_ras_n ( sr_ras_n ),
- .sr_cas_n ( sr_cas_n ),
- .sr_we_n ( sr_we_n ),
- .sr_dqm ( sr_dqm ),
- .sr_ba ( sr_ba ),
- .sr_a ( sr_a ),
- .sr_dq ( sr_dq ),
- .port1 ( sr_bus ),
- .a2 ( sdram_rom_waddr ),
- .wd2 ( sdram_rom_wd ),
- .wrq2 ( sdram_rom_wrq ),
- .wacc2 ( sdram_rom_wacc )
- );
- //
- // ABC-bus interface
- //
- wire abc_clk_s; // abc_clk synchronous to sys_clk
- abcbus #(.mosfet_installed(x_mosfet))
- abcbus (
- .rst_n ( rst_n ),
- .sys_clk ( sys_clk ),
- .sdram_clk ( sdram_clk ),
- .stb_1mhz ( sys_clk_stb[6] ),
- .abc_valid ( iodev_valid_abc ),
- .map_valid ( iodev_valid_abcmemmap ),
- .cpu_addr ( cpu_mem_addr ),
- .cpu_wdata ( cpu_mem_wdata ),
- .cpu_wstrb ( cpu_mem_wstrb ),
- .cpu_rdata ( iodev_rdata_abc ),
- .cpu_rdata_map ( iodev_rdata_abcmemmap ),
- .irq ( iodev_irq_abc ),
- .abc_clk ( abc_clk ),
- .abc_clk_s ( abc_clk_s ),
- .abc_a ( abc_a ),
- .abc_d ( abc_d ),
- .abc_d_oe ( abc_d_oe ),
- .abc_rst_n ( abc_rst_n ),
- .abc_cs_n ( abc_cs_n ),
- .abc_out_n ( abc_out_n ),
- .abc_inp_n ( abc_inp_n ),
- .abc_xmemfl_n ( abc_xmemfl_n ),
- .abc_xmemw800_n ( abc_xmemw800_n ),
- .abc_xmemw80_n ( abc_xmemw80_n ),
- .abc_xinpstb_n ( abc_xinpstb_n ),
- .abc_xoutpstb_n ( abc_xoutpstb_n ),
- .abc_rdy_x ( abc_rdy_x ),
- .abc_resin_x ( abc_resin_x ),
- .abc_int80_x ( abc_int80_x ),
- .abc_int800_x ( abc_int800_x ),
- .abc_nmi_x ( abc_nmi_x ),
- .abc_xm_x ( abc_xm_x ),
- .abc_host ( abc_host ),
- .exth_ha ( exth_ha ),
- .exth_hb ( exth_hb ),
- .exth_hc ( exth_hc ),
- .exth_hd ( exth_hd ),
- .exth_he ( exth_he ),
- .exth_hf ( exth_hf ),
- .exth_hg ( exth_hg ),
- .exth_hh ( exth_hh ),
- .sdram_addr ( abc_sr_addr ),
- .sdram_rd ( abc_sr_rd ),
- .sdram_valid ( abc_sr_valid ),
- .sdram_ready ( abc_sr_ready ),
- .sdram_wd ( abc_sr_wd ),
- .sdram_wstrb ( abc_sr_wstrb )
- );
- // Embedded RISC-V CPU
- // Edge-triggered IRQs. picorv32 latches interrupts
- // but doesn't edge detect for a slow signal, so do it
- // here instead and use level triggered signalling to the
- // CPU. This also allows using an explicit EOI instead of
- // using EOI-on-INTACK.
- //
- // sys_irq defined in iodevs.vh
- reg [31:0] sys_irq_q;
- reg [31:0] cpu_irq;
- wire [31:0] cpu_eoi = {32{sysreg[4]}}
- & {{8{cpu_mem_wstrb[3]}}, {8{cpu_mem_wstrb[2]}},
- {8{cpu_mem_wstrb[1]}}, {8{cpu_mem_wstrb[0]}}}
- & cpu_mem_wdata;
- // Reading the register shows the current set of pending interrupts.
- assign sysreg_rdata[4] = cpu_irq;
- // CPU permanently hung?
- wire cpu_trap;
- // Request to halt the CPU on the next instruction boundary
- wire cpu_halt;
- always @(negedge rst_n or posedge sys_clk)
- if (~rst_n)
- begin
- sys_irq_q <= 32'b0;
- cpu_irq <= 32'b0;
- end
- else
- begin
- sys_irq_q <= sys_irq & irq_edge_mask;
- cpu_irq <= (sys_irq & ~sys_irq_q) |
- (cpu_irq & irq_edge_mask & ~cpu_eoi);
- end
- picorv32 #(
- .ENABLE_COUNTERS ( 1 ),
- .ENABLE_COUNTERS64 ( 1 ),
- .ENABLE_REGS_16_31 ( 1 ),
- .ENABLE_REGS_DUALPORT ( 1 ),
- .LATCHED_MEM_RDATA ( 0 ),
- .BARREL_SHIFTER ( 1 ),
- .TWO_CYCLE_COMPARE ( 0 ),
- .TWO_CYCLE_ALU ( 0 ),
- .COMPRESSED_ISA ( 1 ),
- .CATCH_MISALIGN ( 1 ),
- .CATCH_ILLINSN ( 1 ),
- .ENABLE_FAST_MUL ( 1 ),
- .ENABLE_DIV ( 1 ),
- .ENABLE_IRQ ( 1 ),
- .ENABLE_IRQ_QREGS ( 1 ),
- .ENABLE_IRQ_TIMER ( 1 ),
- .MASKED_IRQ ( irq_masked ),
- .LATCHED_IRQ ( 32'h0000_0007 ),
- .REGS_INIT_ZERO ( 1 ),
- .STACKADDR ( 1'b1 << SRAM_BITS ),
- .USER_CONTEXTS ( 7 )
- ) cpu (
- .clk ( sys_clk ),
- .resetn ( rst_n ),
- .halt ( cpu_halt ),
- .trap ( cpu_trap ),
- .progaddr_reset ( _PC_RESET ),
- .progaddr_irq ( _PC_IRQ ),
- .mem_instr ( cpu_mem_instr ),
- .mem_ready ( cpu_mem_ready ),
- .mem_valid ( cpu_mem_valid ),
- .mem_wstrb ( cpu_mem_wstrb ),
- .mem_addr ( cpu_mem_addr ),
- .mem_wdata ( cpu_mem_wdata ),
- .mem_rdata ( cpu_mem_rdata ),
- .mem_la_read ( cpu_la_read ),
- .mem_la_write ( cpu_la_write ),
- .mem_la_wdata ( cpu_la_wdata ),
- .mem_la_addr ( cpu_la_addr ),
- .mem_la_wstrb ( cpu_la_wstrb ),
- .irq ( cpu_irq ),
- .eoi ( )
- );
- // Add a mandatory wait state to iodevs to reduce the size
- // of the CPU memory input MUX (it hurts timing on memory
- // accesses...)
- reg iodev_mem_ready;
- assign cpu_mem_ready =
- (cpu_mem_quad[0] & 1'b1) |
- (cpu_mem_quad[1] & sdram_mem_ready) |
- (cpu_mem_quad[2] & 1'b1) |
- (cpu_mem_quad[3] & iodev_mem_ready);
- //
- // Fast memory. This runs on the SDRAM clock, i.e. 2x the speed
- // of the CPU. The .bits parameter gives the number of dwords
- // as a power of 2, i.e. 11 = 2^11 * 4 = 8K.
- //
- wire [31:0] fast_mem_rdata;
- wire [SRAM_BITS-1:2] vjtag_sram_addr;
- wire vjtag_sram_read;
- wire vjtag_sram_write;
- wire [31:0] vjtag_sram_rdata;
- wire [31:0] vjtag_sram_wdata;
- fast_mem #(.words_lg2(SRAM_BITS-2),
- .data_file("mif/sram.mif"))
- fast_mem(
- .rst_n ( rst_n ),
- .clk ( sys_clk ),
- .read0 ( 1'b1 ), // cpu_la_read & cpu_la_addr[31:30] == 2'b00
- .write0 ( cpu_la_write & cpu_la_addr[31:30] == 2'b00 ),
- .wstrb0 ( cpu_la_wstrb ),
- .addr0 ( cpu_la_addr[SRAM_BITS-1:2] ),
- .wdata0 ( cpu_la_wdata ),
- .rdata0 ( fast_mem_rdata ),
- .read1 ( 1'b1 ), // vjtag_sram_read
- .write1 ( vjtag_sram_write ),
- .wstrb1 ( 4'b1111 ),
- .addr1 ( vjtag_sram_addr ),
- .wdata1 ( vjtag_sram_wdata ),
- .rdata1 ( vjtag_sram_rdata )
- );
- // Register I/O data to reduce the size of the read data MUX
- reg [31:0] iodev_rdata_q;
- // Read data MUX
- always_comb
- case ( cpu_mem_quad )
- 4'b0001: cpu_mem_rdata = fast_mem_rdata;
- 4'b0010: cpu_mem_rdata = sdram_mem_rdata;
- 4'b1000: cpu_mem_rdata = iodev_rdata_q;
- default: cpu_mem_rdata = 32'hxxxx_xxxx;
- endcase
- // Miscellaneous system control/status registers
- wire [ 4:0] sysreg_subreg = cpu_mem_addr[6:2];
- wire [31:0] sysreg = iodev_valid_sys << sysreg_subreg;
- tri1 [31:0] sysreg_rdata[0:31];
- assign iodev_rdata_sys = sysreg_rdata[sysreg_subreg];
- //
- // Board identification
- //
- // Magic number: "MAX8"
- // Board revision: 1.0/2.0
- // Board rework flags:
- // [7:0] - reserved
- //
- wire rtc_32khz_rework = 1'b1;
- reg board_id_q;
- always @(posedge sys_clk)
- board_id_q <= board_id;
- wire [ 7:0] max80_fpga = fpga_ver;
- wire [ 7:0] max80_major = ~board_id_q ? 8'd2 : 8'd1;
- wire [ 7:0] max80_minor = 8'd0;
- wire [ 7:0] max80_fixes = 8'b0;
- assign sysreg_rdata[0] = SYS_MAGIC_MAX80;
- assign sysreg_rdata[1] = { max80_fpga, max80_major,
- max80_minor, max80_fixes };
- // System reset
- wire usb_rxd_break_rst; // Reset due to USB serial port BREAK
- wire tty_rxd_break_rst; // Reset due to TTY serial port BREAK
- wire vjtag_reset_cmd; // Reset due to virtual JTAG request
- // Reset control. Note that CPU reset command 0 is a noop.
- wire [3:0] cpu_reset_io_cmd =
- (sysreg[3] & cpu_mem_wstrb[0]) << cpu_mem_wdata[1:0];
- //
- // Soft system reset: FPGA not reloaded, PLLs not reset,
- // USB and console are not reset
- //
- // Triggered by:
- // - CPU reset command 1
- // - CPU entering TRAP state (irrecoverable error)
- // - BREAK received on console
- // - VJTAG request
- //
- assign cpu_reset_cmd[1] = cpu_reset_io_cmd[1] | cpu_trap;
- assign aux_reset_cmd[1] = usb_rxd_break_rst | tty_rxd_break_rst |
- vjtag_reset_cmd;
- //
- // Hard system reset: FPGA not reloaded, PLLs reset, all hw units reset
- //
- assign cpu_reset_cmd[2] = cpu_reset_io_cmd[2];
- assign aux_reset_cmd[2] = 1'b0;
- //
- // FPGA reload reset (not implemented yet)
- //
- assign cpu_reset_cmd[3] = cpu_reset_io_cmd[3];
- assign aux_reset_cmd[3] = 1'b0;
- // LED indication from the CPU
- reg [2:0] led_q;
- always @(negedge rst_n or posedge sys_clk)
- if (~rst_n)
- led_q <= 3'b000;
- else
- if ( sysreg[2] & cpu_mem_wstrb[0] )
- led_q <= cpu_mem_wdata[2:0];
- assign led = led_q;
- assign sysreg_rdata[2] = { 29'b0, led_q };
- // Random number generator
- wire rtc_clk_s;
- rng #(.nclocks(2), .width(32)) rng
- (
- .rst_n ( rst_n ),
- .sys_clk ( sys_clk ),
- .read_stb ( iodev_valid_random ),
- .latch_stb ( sys_clk_stb[16] ),
- .ready ( iodev_irq_random ),
- .q ( iodev_rdata_random ),
- .clocks ( { rtc_clk_s, abc_clk_s } ),
- .rngio ( rngio )
- );
- //
- // Serial ROM (also configuration ROM.) Fast hardwired data download
- // unit to SDRAM.
- //
- wire rom_done;
- reg rom_done_q;
- spirom ddu (
- .rst_n ( rst_n ),
- .rom_clk ( flash_clk ),
- .ram_clk ( sdram_clk ),
- .sys_clk ( sys_clk ),
- .spi_sck ( flash_sck ),
- .spi_io ( flash_io ),
- .spi_cs_n ( flash_cs_n ),
- .wd ( sdram_rom_wd ),
- .waddr ( sdram_rom_waddr ),
- .wrq ( sdram_rom_wrq ),
- .wacc ( sdram_rom_wacc ),
- .cpu_rdata ( iodev_rdata_romcopy ),
- .cpu_wdata ( cpu_mem_wdata ),
- .cpu_valid ( iodev_valid_romcopy ),
- .cpu_wstrb ( cpu_mem_wstrb ),
- .cpu_addr ( cpu_mem_addr[4:2] ),
- .irq ( iodev_irq_romcopy )
- );
- //
- // Serial port. Direct to the CP2102N for v1 boards
- // boards or to GPIO for v2 boards.
- //
- wire tty_data_out; // Output data
- wire tty_data_in; // Input data
- wire tty_cts_out; // Assert CTS# externally
- wire tty_rts_in; // RTS# received from outside
- wire tty_dtr_in; // DTR# received from outside
- assign tty_data_in = tty_txd;
- assign tty_rxd = tty_data_out;
- assign tty_rts_in = ~tty_rts;
- assign tty_dtr_in = ~tty_dtr;
- assign tty_cts = ~tty_cts_out;
- assign tty_cts_out = 1'b1; // Always assert CTS# for now
- // The physical tty now just snoops USB ACM channel 0; as such it does
- // not respond to any write requests nor issue any irqs
- wire serial_tx_full;
- wire serial_rx_break;
- serial #(.ENABLE_RX_DATA (1'b0),
- .ENABLE_RX_BREAK (1'b1),
- .ENABLE_TX_DATA (1'b1),
- .ENABLE_TX_BREAK (1'b0),
- .BAUDRATE_SETTABLE (1'b0),
- .BAUDRATE (921600),
- .TTY_CLK (84000000))
- (
- .rst_n ( hard_rst_n ),
- .clk ( sys_clk ),
- // Snoops USB TTY channel 0
- .tx_wstrb ( iodev_valid_tty &
- cpu_mem_addr[6:2] == 5'b00000 &
- cpu_mem_wstrb[0] ),
- .tx_data ( cpu_mem_wdata[7:0] ),
- .tx_flush ( 1'b0 ),
- .rx_flush ( 1'b0 ),
- .tty_rx ( tty_data_in ),
- .tty_tx ( tty_data_out ),
- .tx_full ( serial_tx_full ),
- .rx_break ( tty_rxd_break_rst )
- );
- // If DTR# is asserted, block on full serial Tx FIFO; this allows
- // us to not lose debugging messages.
- assign iodev_wait_n_tty = ~(serial_tx_full & tty_dtr_in);
- max80_usb #( .channels( TTY_CHANNELS ) ) usb (
- .hard_rst_n ( hard_rst_n ),
- .clock48 ( usb_clk ),
- .rst_n ( rst_n ),
- .sys_clk ( sys_clk ),
- .cpu_valid_usbdesc ( iodev_valid_usbdesc ),
- .cpu_valid_cdc ( iodev_valid_tty ),
- .cpu_addr ( cpu_mem_addr ),
- .cpu_rdata_usbdesc ( iodev_rdata_usbdesc ),
- .cpu_rdata_cdc ( iodev_rdata_tty ),
- .cpu_wdata ( cpu_mem_wdata ),
- .cpu_wstrb ( cpu_mem_wstrb ),
- .irq ( iodev_irq_tty ),
- .tty_rxd_break ( usb_rxd_break_rst ),
- .usb_dp ( usb_dp ),
- .usb_dn ( usb_dn ),
- .usb_pu ( usb_pu ),
- .usb_rx ( usb_rx ),
- .usb_rx_ok ( usb_rx_ok )
- );
- // SD card
- sdcard #(
- .with_irq_mask ( 8'b0000_0001 )
- )
- sdcard (
- .rst_n ( rst_n ),
- .clk ( sys_clk ),
- .sd_cs_n ( sd_cs_n ),
- .sd_di ( sd_di ),
- .sd_sclk ( sd_clk ),
- .sd_do ( sd_do ),
- .sd_cd_n ( sd_cd_n ),
- .sd_irq_n ( 1'b1 ),
- .wdata ( cpu_mem_wdata ),
- .rdata ( iodev_rdata_sdcard ),
- .valid ( iodev_valid_sdcard ),
- .wstrb ( cpu_mem_wstrb ),
- .addr ( cpu_mem_addr[6:2] ),
- .wait_n ( iodev_wait_n_sdcard ),
- .irq ( iodev_irq_sdcard )
- );
- //
- // System local clock (not an RTC per se, but settable from one);
- // also provides a periodic interrupt, currently set to 32 Hz.
- //
- // The RTC 32.768 kHz output is open drain, so use the negative
- // edge for clocking.
- //
- wire clk_32kHz = ~rtc_32khz; // Inverted
- wire [15:0] rtc_ctr;
- sysclock #(.PERIODIC_HZ_LG2 ( TIMER_SHIFT ))
- sysclock (
- .rst_n ( rst_n ),
- .sys_clk ( sys_clk ),
- .rtc_clk ( clk_32kHz ),
- .rtc_clk_s ( rtc_clk_s ),
- .wdata ( cpu_mem_wdata ),
- .rdata ( iodev_rdata_sysclock ),
- .valid ( iodev_valid_sysclock ),
- .wstrb ( cpu_mem_wstrb ),
- .addr ( cpu_mem_addr[2] ),
- .periodic ( iodev_irq_sysclock ),
- .rtc_ctr ( rtc_ctr )
- );
- // ESP32
- assign spi_cs_flash_n = 1'bz;
- esp esp (
- .rst_n ( rst_n ),
- .sys_clk ( sys_clk ),
- .sdram_clk ( sdram_clk ),
- .cpu_valid ( iodev_valid_esp ),
- .cpu_addr ( cpu_mem_addr[6:2] ),
- .cpu_wstrb ( cpu_mem_wstrb ),
- .cpu_wdata ( cpu_mem_wdata ),
- .cpu_rdata ( iodev_rdata_esp ),
- .irq ( iodev_irq_esp ),
- .esp_int ( esp_int ),
- .spi_clk ( spi_clk ),
- .spi_io ( spi_io ),
- .spi_cs_n ( spi_cs_esp_n ),
- .dram ( sr_bus[2].dstr ),
- .rtc_ctr ( rtc_ctr )
- );
- //
- // I2C bus (RTC and to connector)
- //
- i2c i2c (
- .rst_n ( rst_n ),
- .clk ( sys_clk ),
- .valid ( iodev_valid_i2c ),
- .addr ( cpu_mem_addr[3:2] ),
- .wdata ( cpu_mem_wdata ),
- .wstrb ( cpu_mem_wstrb ),
- .rdata ( iodev_rdata_i2c ),
- .irq ( iodev_irq_i2c ),
- .i2c_scl ( i2c_scl ),
- .i2c_sda ( i2c_sda )
- );
- // Virtual JTAG interface
- wire vjtag_cpu_halt;
- vjtag_max80 #(.sdram_base_addr(SDRAM_ADDR),
- .sdram_bits(SDRAM_BITS),
- .sram_bits(SRAM_BITS))
- vjtag (
- .rst_n ( rst_n ),
- .sys_clk ( sys_clk ),
- .reset_cmd ( vjtag_reset_cmd ),
- .sdram ( sr_bus[3].dstr ),
- .cpu_valid ( iodev_valid_vjtag ),
- .cpu_addr ( cpu_mem_addr[6:2] ),
- .cpu_wdata ( cpu_mem_wdata ),
- .cpu_wstrb ( cpu_mem_wstrb ),
- .cpu_rdata ( iodev_rdata_vjtag ),
- .cpu_irq ( iodev_irq_vjtag ),
- .cpu_halt ( vjtag_cpu_halt ),
- .sram_addr ( vjtag_sram_addr ),
- .sram_rdata ( vjtag_sram_rdata ),
- .sram_wdata ( vjtag_sram_wdata ),
- .sram_read ( vjtag_sram_read ),
- .sram_write ( vjtag_sram_write )
- );
- assign cpu_halt = vjtag_cpu_halt;
- //
- // Registering of I/O data and handling of iodev_mem_ready
- //
- always @(posedge sys_clk)
- iodev_rdata_q <= iodev_rdata;
- always @(negedge rst_n or posedge sys_clk)
- if (~rst_n)
- iodev_mem_ready <= 1'b0;
- else
- iodev_mem_ready <= iodev_wait_n & cpu_mem_valid;
- endmodule
|