You dont have javascript enabled! Please enable it!

Practical case: Modbus TCP gateway for iCEBreaker/MCP23S17

Practical case: Modbus TCP gateway for iCEBreaker/MCP23S17 — hero

Objective and use case

What you’ll build: A Modbus-TCP I/O gateway using the iCEBreaker iCE40UP5K FPGA, which exposes 16 digital I/O points through an MCP23S17 GPIO expander, serving Modbus-TCP on port 502 via a WIZ850io (W5500) Ethernet module.

Why it matters / Use cases

  • Enables remote monitoring and control of digital I/O devices in industrial automation systems.
  • Facilitates integration of legacy devices into modern IoT architectures using Modbus-TCP protocol.
  • Supports real-time data acquisition for smart building applications, such as lighting and HVAC control.
  • Provides a cost-effective solution for small-scale automation projects without proprietary hardware.

Expected outcome

  • Achieve reliable communication with latencies under 10ms for Modbus requests.
  • Handle up to 100 packets/s for reading and writing I/O states.
  • Demonstrate the ability to read/write 16 digital I/O points with less than 5% packet loss.
  • Maintain a stable connection with a throughput of at least 1 Mbps over the Ethernet link.

Audience: Engineers and developers familiar with FPGA design; Level: Advanced Hands-On.

Architecture/flow: The design utilizes an FPGA to orchestrate SPI communication with the MCP23S17 and WIZ850io, implementing Modbus-TCP parsing for data exchange.

Advanced Hands‑On: Modbus‑TCP I/O Gateway on iCEBreaker iCE40UP5K with WIZ850io (W5500) and MCP23S17

Objective: Build a hardware Modbus‑TCP I/O gateway using the iCEBreaker iCE40UP5K FPGA that exposes 16 digital I/O points through an MCP23S17 GPIO expander. The gateway serves Modbus‑TCP on port 502 using a WIZ850io (W5500) hard‑TCP/IP Ethernet module over SPI. The FPGA orchestrates both SPI peripherals and implements minimal Modbus‑TCP parsing to read/write coils and read holding registers.

The design is fully open‑source toolchain based: yosys + nextpnr‑ice40 + icestorm + openFPGALoader. All steps are scripted and reproducible.


Prerequisites

  • Strong familiarity with Verilog RTL and finite state machines.
  • Comfortable with SPI timing and memory‑mapped register interactions.
  • Understanding of Modbus‑TCP ADU (MBAP header + PDU) and basic function codes:
  • 0x01 Read Coils
  • 0x02 Read Discrete Inputs
  • 0x03 Read Holding Registers
  • 0x05 Write Single Coil
  • Linux or macOS with shell access, and Ethernet connectivity to a local subnet.
  • Admin rights to install packages and set static IPs on your host if needed.

Toolchain versions used and tested:
– yosys 0.40
– nextpnr‑ice40 0.4
– icestorm (icepack) 0.1
– openFPGALoader 0.12

Modbus test tools (pick one):
– mbpoll 1.5.1 (preferred CLI)
– pymodbus 3.6.5 (Python 3.10+)
– Wireshark 4.x (for packet capture validation)


Materials (exact models)

  • FPGA board: iCEBreaker iCE40UP5K (1BitSquared, UP5K‑SG48, 12 MHz oscillator)
  • Ethernet module: WIZ850io (W5500)
  • GPIO expander: MCP23S17‑E/SS (SPI variant)
  • Cables:
  • USB‑C cable for iCEBreaker programming
  • Ethernet cable for WIZ850io to switch/router/PC
  • 3.3 V logic jumper wires for connections (M‑M or M‑F as appropriate)
  • Power: Use the iCEBreaker’s 3.3 V from PMOD/VCC to power both modules

Notes:
– The WIZ850io requires only 3.3 V logic.
– MCP23S17 also works at 3.3 V; tie address pins A0..A2 to GND for address 0x00.


Setup/Connection

We will share one SPI bus (SCK, MOSI, MISO) between WIZ850io and MCP23S17, with distinct chip‑select lines. We also use reset and interrupt lines for robustness.

  • SPI mode:
  • W5500: SPI Mode 0 (CPOL=0, CPHA=0)
  • MCP23S17: SPI Mode 0
  • Max SPI frequency:
  • W5500 supports >20 MHz; we will use 6 MHz for safety
  • MCP23S17 allows up to 10 MHz; 6 MHz is safe

Assumptions:
– We will use the iCEBreaker official PCF for clock, LEDs, and PMOD nets to avoid package‑pin errors.
– We will directly name our Verilog ports to match the canonical PCF net names.

Download the canonical iCEBreaker PCF:
– constraints/icebreaker.pcf from:
https://raw.githubusercontent.com/icebreaker-fpga/icebreaker-examples/master/constraints/icebreaker.pcf

We will use the following net names in our top module:
– CLK (12 MHz)
– LED_R, LED_G, LED_B (on‑board RGB for status)
– PMOD1A_1..PMOD1A_8 (for SPI and control)
– PMOD1B_1..PMOD1B_8 (optional, not strictly needed here)

Wiring plan (all logic 3.3 V):

  • Shared SPI bus:
  • PMOD1A_1 → SPI_SCK → WIZ850io SCLK, MCP23S17 SCK
  • PMOD1A_2 → SPI_MOSI → WIZ850io MOSI, MCP23S17 SI
  • PMOD1A_3 ← SPI_MISO ← WIZ850io MISO, MCP23S17 SO

  • Chip selects:

  • PMOD1A_4 → CS_W5500 → WIZ850io SCSn (active low)
  • PMOD1A_7 → CS_MCP → MCP23S17 CS (active low)

  • Resets/Interrupts:

  • PMOD1A_8 → W5500_RSTn → WIZ850io RSTn (active low; we will drive low then high)
  • PMOD1A_6 → MCP_RSTn → MCP23S17 RESET (active low; we will drive high, but keep as controllable)
  • PMOD1A_5 ← W5500_INTn ← WIZ850io INTn (active low to signal events; optional but recommended)

  • Power and GND:

  • PMOD VCC (3.3 V) → WIZ850io 3V3, MCP23S17 VDD
  • PMOD GND → WIZ850io GND, MCP23S17 VSS
  • MCP23S17 Address pins A0, A1, A2 → GND (device address 0)

  • MCP23S17 ports:

  • GPIOA[7:0], GPIOB[7:0] via your wire harness to your target digital I/O
  • For this tutorial, connect LEDs (with appropriate resistors) to a few outputs and switches to inputs.

Mapping summary:

Signal iCEBreaker net WIZ850io pin MCP23S17 pin Notes
SPI_SCK PMOD1A_1 SCLK SCK Shared SPI clock
SPI_MOSI PMOD1A_2 MOSI SI Shared MOSI
SPI_MISO PMOD1A_3 MISO SO Shared MISO
CS_W5500 (n) PMOD1A_4 SCSn Active‑low CS for W5500
W5500_INTn PMOD1A_5 INTn Optional event line from W5500
MCP_RSTn (n) PMOD1A_6 RESET Active‑low reset for MCP
CS_MCP (n) PMOD1A_7 CS Active‑low CS for MCP23S17
W5500_RSTn (n) PMOD1A_8 RSTn Active‑low reset for W5500
3.3 V / GND PMOD VCC/GND 3V3/GND VDD/VSS Common power and ground

Ensure a stable network connection:
– Connect WIZ850io RJ45 to a switch/router on 192.168.50.0/24 (or your target subnet).
– We will configure FPGA to static IP 192.168.50.2, MAC 02:12:34:56:78:9A, gateway 192.168.50.1, subnet 255.255.255.0.


Full Code

Files:
– rtl/top.v
– rtl/spi_simple.v
– rtl/w5500_if.v
– rtl/mcp23s17_if.v

This is a compact, single‑clock (12 MHz) design. The SPI clock is generated by division.

rtl/spi_simple.v

A minimal SPI Mode 0 engine with byte streaming and external CS control. One transaction is a sequence of bytes; assert cs_n low externally and call start for each byte.

// rtl/spi_simple.v
// Simple SPI Mode 0 master, MSB first, byte-wide API
module spi_simple #(
    parameter DIV = 2  // generates SCK = fclk / (2*DIV); with 12MHz and DIV=1 => 6MHz
)(
    input  wire       clk,
    input  wire       rst,

    // Byte interface
    input  wire       start,       // pulse to start transmitting 'tx_byte'
    input  wire [7:0] tx_byte,
    output reg  [7:0] rx_byte,
    output reg        busy,        // high during transfer
    output reg        done,        // 1clk pulse when a byte completes

    // SPI lines
    output reg        sck,
    output reg        mosi,
    input  wire       miso
);
    localparam IDLE=0, HOLD=1, SHIFT=2;
    reg [1:0]  state;
    reg [7:0]  shreg_tx;
    reg [7:0]  shreg_rx;
    reg [3:0]  bitcnt;
    reg [7:0]  divcnt;

    always @(posedge clk or posedge rst) begin
        if (rst) begin
            state   <= IDLE;
            sck     <= 1'b0;
            mosi    <= 1'b0;
            rx_byte <= 8'h00;
            busy    <= 1'b0;
            done    <= 1'b0;
            bitcnt  <= 4'd0;
            divcnt  <= 8'd0;
        end else begin
            done <= 1'b0;
            case (state)
                IDLE: begin
                    sck  <= 1'b0;
                    busy <= 1'b0;
                    if (start) begin
                        shreg_tx <= tx_byte;
                        shreg_rx <= 8'h00;
                        bitcnt   <= 4'd8;
                        busy     <= 1'b1;
                        // MSB first: output first bit before first rising edge
                        mosi     <= tx_byte[7];
                        state    <= HOLD;
                        divcnt   <= 0;
                    end
                end
                HOLD: begin
                    // Wait DIV clocks then toggle SCK
                    divcnt <= divcnt + 1;
                    if (divcnt == (DIV-1)) begin
                        divcnt <= 0;
                        sck    <= ~sck;
                        if (sck == 1'b0) begin
                            // rising edge: sample MISO
                            shreg_rx <= {shreg_rx[6:0], miso};
                        end else begin
                            // falling edge: shift out next MOSI
                            if (bitcnt != 0) begin
                                shreg_tx <= {shreg_tx[6:0], 1'b0};
                                mosi     <= shreg_tx[6];
                                bitcnt   <= bitcnt - 1;
                            end
                            if (bitcnt == 1) begin
                                state <= SHIFT;
                            end
                        end
                    end
                end
                SHIFT: begin
                    // Finish last falling edge, capture result
                    if (sck == 1'b0) begin
                        rx_byte <= shreg_rx;
                        done    <= 1'b1;
                        busy    <= 1'b0;
                        state   <= IDLE;
                    end else begin
                        // ensure we return to sck=0
                        divcnt <= divcnt + 1;
                        if (divcnt == (DIV-1)) begin
                            divcnt <= 0;
                            sck    <= 1'b0;
                        end
                    end
                end
            endcase
        end
    end
endmodule

rtl/mcp23s17_if.v

Tiny driver to initialize MCP23S17 and read/write its GPIO A/B as coils. Address pins set to 0 -> opcode base 0x40 (write), 0x41 (read).

// rtl/mcp23s17_if.v
// Minimal MCP23S17 interface: configure, read GPIO, write OLAT
module mcp23s17_if #(
    parameter DIV = 2  // SPI divider for spi_simple
)(
    input  wire       clk,
    input  wire       rst,
    // SPI master connection
    output wire       sck,
    output wire       mosi,
    input  wire       miso,
    output reg        cs_n,
    output reg        rst_n,

    // Simple register access
    input  wire       req_read,       // pulse to read both ports
    output reg        rd_valid,
    output reg [7:0]  gpioa,
    output reg [7:0]  gpiob,

    input  wire       req_write,      // pulse to write both ports
    input  wire [7:0] olata,
    input  wire [7:0] olatb,
    output reg        wr_done
);
    // MCP23S17 register addresses (BANK=0)
    localparam IODIRA = 8'h00, IODIRB = 8'h01;
    localparam GPIOA  = 8'h12, GPIOB  = 8'h13;
    localparam OLATA  = 8'h14, OLATB  = 8'h15;

    // SPI opcodes for address 0: write=0x40, read=0x41
    localparam OPC_WR = 8'h40;
    localparam OPC_RD = 8'h41;

    // Instantiate SPI engine
    reg        spi_start;
    reg [7:0]  spi_tx;
    wire [7:0] spi_rx;
    wire       spi_busy, spi_done;

    spi_simple #(.DIV(DIV)) SPI (
        .clk(clk), .rst(rst),
        .start(spi_start),
        .tx_byte(spi_tx),
        .rx_byte(spi_rx),
        .busy(spi_busy), .done(spi_done),
        .sck(sck), .mosi(mosi), .miso(miso)
    );

    // State machine: init → idle → read/write ops
    localparam S_RST=0, S_INIT0=1, S_INIT1=2, S_IDLE=3,
               S_R0=4, S_R1=5, S_R2=6,
               S_W0=7, S_W1=8, S_W2=9, S_W3=10;
    reg [3:0]  st;
    reg [7:0]  tmpa, tmpb;
    reg [2:0]  bcnt;

    always @(posedge clk or posedge rst) begin
        if (rst) begin
            st       <= S_RST;
            cs_n     <= 1'b1;
            rst_n    <= 1'b0;    // hold MCP reset low
            spi_start<= 1'b0;
            rd_valid <= 1'b0;
            wr_done  <= 1'b0;
            gpioa    <= 8'h00;
            gpiob    <= 8'h00;
            bcnt     <= 3'd0;
        end else begin
            spi_start <= 1'b0;
            rd_valid  <= 1'b0;
            wr_done   <= 1'b0;
            case (st)
                S_RST: begin
                    // deassert reset after some cycles
                    rst_n <= 1'b1;
                    st    <= S_INIT0;
                end
                S_INIT0: begin
                    // Write IODIRA=0x00 (all outputs), IODIRB=0xFF (all inputs) for demo
                    // You can adjust per your needs.
                    cs_n     <= 1'b0;
                    bcnt     <= 3'd0;
                    st       <= S_INIT1;
                end
                S_INIT1: begin
                    if (!spi_busy && !spi_start) begin
                        case (bcnt)
                            3'd0: begin spi_tx <= OPC_WR; spi_start <= 1'b1; bcnt <= 3'd1; end
                            3'd1: begin if (spi_done) begin spi_tx <= IODIRA; spi_start <= 1'b1; bcnt <= 3'd2; end end
                            3'd2: begin if (spi_done) begin spi_tx <= 8'h00;   spi_start <= 1'b1; bcnt <= 3'd3; end end
                            3'd3: begin if (spi_done) begin spi_tx <= OPC_WR; spi_start <= 1'b1; bcnt <= 3'd4; end end
                            3'd4: begin if (spi_done) begin spi_tx <= IODIRB; spi_start <= 1'b1; bcnt <= 3'd5; end end
                            3'd5: begin if (spi_done) begin spi_tx <= 8'hFF;   spi_start <= 1'b1; bcnt <= 3'd6; end end
                            3'd6: begin if (spi_done) begin cs_n<=1'b1; st<=S_IDLE; end end
                        endcase
                    end
                end
                S_IDLE: begin
                    if (req_read) begin
                        cs_n <= 1'b0; bcnt <= 0; st <= S_R0;
                    end else if (req_write) begin
                        cs_n <= 1'b0; bcnt <= 0; st <= S_W0;
                    end
                end
                // Read GPIOA then GPIOB
                S_R0: begin
                    if (!spi_busy && !spi_start) begin
                        case (bcnt)
                            3'd0: begin spi_tx<=OPC_RD; spi_start<=1'b1; bcnt<=3'd1; end
                            3'd1: begin if (spi_done) begin spi_tx<=GPIOA; spi_start<=1'b1; bcnt<=3'd2; end end
                            3'd2: begin if (spi_done) begin spi_tx<=8'h00;  spi_start<=1'b1; bcnt<=3'd3; end end // dummy to read GPIOA
                            3'd3: begin if (spi_done) begin tmpa<=spi_rx;  bcnt<=3'd4; end end
                            3'd4: begin spi_tx<=OPC_RD; spi_start<=1'b1; st<=S_R1; end
                        endcase
                    end
                end
                S_R1: begin
                    if (spi_done) begin
                        spi_tx<=GPIOB; spi_start<=1'b1; st<=S_R2;
                    end
                end
                S_R2: begin
                    if (spi_done) begin
                        spi_tx<=8'h00; spi_start<=1'b1;
                        st<=S_IDLE;
                    end else if (!spi_busy && !spi_start && cs_n==1'b0) begin
                        // wait
                    end
                    if (spi_done) begin
                        tmpb   <= spi_rx;
                        gpioa  <= tmpa;
                        gpiob  <= spi_rx;
                        rd_valid <= 1'b1;
                        cs_n   <= 1'b1;
                    end
                end
                // Write OLATA and OLATB
                S_W0: begin
                    if (!spi_busy && !spi_start) begin
                        case (bcnt)
                            3'd0: begin spi_tx<=OPC_WR; spi_start<=1'b1; bcnt<=3'd1; end
                            3'd1: begin if (spi_done) begin spi_tx<=OLATA; spi_start<=1'b1; bcnt<=3'd2; end end
                            3'd2: begin if (spi_done) begin spi_tx<=olata; spi_start<=1'b1; bcnt<=3'd3; end end
                            3'd3: begin if (spi_done) begin spi_tx<=OPC_WR; spi_start<=1'b1; bcnt<=3'd4; end end
                            3'd4: begin if (spi_done) begin spi_tx<=OLATB; spi_start<=1'b1; bcnt<=3'd5; end end
                            3'd5: begin if (spi_done) begin spi_tx<=olatb; spi_start<=1'b1; bcnt<=3'd6; end end
                            3'd6: begin if (spi_done) begin cs_n<=1'b1; wr_done<=1'b1; st<=S_IDLE; end end
                        endcase
                    end
                end
            endcase
        end
    end
endmodule

rtl/w5500_if.v

Minimal W5500 controller that:
– Resets and configures common registers (gateway, subnet, MAC, IP).
– Configures socket 0 TX/RX memory.
– Opens socket 0 in TCP, listens on port 502.
– Accepts one client. For each packet:
– Reads MBAP (7 bytes): Transaction ID, Protocol ID=0, Length, Unit ID.
– Reads PDU and handles FC 0x01, 0x02, 0x03, 0x05 for small ranges.
– Uses simple shared interface signals to request MCP reads/writes.
– Builds response and sends via socket 0.
– Uses W5500 internal pointers Sn_RX_RD, Sn_TX_WR, and commands RECV/SEND.

Note: For brevity, this implementation handles a single request at a time and limits PDU size.

// rtl/w5500_if.v
// Minimal W5500 TCP server on port 502, single socket (S0)
module w5500_if #(
    parameter DIV = 2, // SPI divider for spi_simple
    // Network parameters
    parameter [31:0] GATEWAY = 32'hC0A83201, // 192.168.50.1
    parameter [31:0] SUBNET  = 32'hFFFFFF00, // 255.255.255.0
    parameter [47:0] MAC     = 48'h02123456789A,
    parameter [31:0] IPADDR  = 32'hC0A83202  // 192.168.50.2
)(
    input  wire       clk,
    input  wire       rst,

    // SPI
    output wire       sck,
    output wire       mosi,
    input  wire       miso,
    output reg        cs_n,

    // Control
    output reg        rst_n,
    input  wire       int_n,

    // Application interface to MCP (coils/regs)
    output reg        mcp_req_read,
    input  wire       mcp_rd_valid,
    input  wire [7:0] mcp_gpioa,
    input  wire [7:0] mcp_gpiob,

    output reg        mcp_req_write,
    output reg [7:0]  mcp_olata,
    output reg [7:0]  mcp_olatb,
    input  wire       mcp_wr_done,

    // Status LED indicator
    output reg        link_led   // toggles on activity
);
    // W5500 register addresses and commands
    // Common regs (block=0x00)
    localparam GAR0   = 16'h0001; // 4 bytes
    localparam SUBR0  = 16'h0005; // 4 bytes
    localparam SHAR0  = 16'h0009; // 6 bytes
    localparam SIPR0  = 16'h000F; // 4 bytes
    localparam RMSR   = 16'h001A;
    localparam TMSR   = 16'h001B;

    // Socket 0 registers base 0x0000 in Socket block
    localparam S0_MR   = 16'h0000;
    localparam S0_CR   = 16'h0001;
    localparam S0_IR   = 16'h0002;
    localparam S0_SR   = 16'h0003;
    localparam S0_PORT = 16'h0004; // 2 bytes
    localparam S0_RX_RSR0 = 16'h0026; // 2 bytes
    localparam S0_RX_RD0  = 16'h0028; // 2 bytes
    localparam S0_TX_WR0  = 16'h0024; // 2 bytes

    // Socket commands
    localparam CR_OPEN   = 8'h01;
    localparam CR_LISTEN = 8'h02;
    localparam CR_RECV   = 8'h40;
    localparam CR_SEND   = 8'h20;

    // Socket modes
    localparam MR_TCP = 8'h01;

    // Socket status
    localparam SR_CLOSED       = 8'h00;
    localparam SR_INIT         = 8'h13;
    localparam SR_LISTEN       = 8'h14;
    localparam SR_ESTABLISHED  = 8'h17;
    localparam SR_CLOSE_WAIT   = 8'h1C;

    // SPI engine
    reg        spi_start;
    reg [7:0]  spi_tx;
    wire [7:0] spi_rx;
    wire       spi_busy, spi_done;

    spi_simple #(.DIV(DIV)) SPI (
        .clk(clk), .rst(rst),
        .start(spi_start),
        .tx_byte(spi_tx),
        .rx_byte(spi_rx),
        .busy(spi_busy), .done(spi_done),
        .sck(sck), .mosi(mosi), .miso(miso)
    );

    // W5500 SPI frame header: [Control byte: bsb(5) RWB(1) OM(2)] + [Addr high] + [Addr low]
    // We'll implement helpers to read/write common regs and socket 0 regs,
    // and read/write RX/TX buffers.
    function [7:0] mk_ctrl;
        input [4:0] bsb; // block select
        input       rwb; // 1=read,0=write
        input [1:0] om;  // 00=var length
        begin mk_ctrl = {bsb, rwb, om}; end
    endfunction

    // BSB values
    localparam BSB_COMMON = 5'b00000;
    localparam BSB_S0_REG = 5'b00001;
    localparam BSB_S0_TX  = 5'b00010;
    localparam BSB_S0_RX  = 5'b00011;

    // Simple micro‑ops
    reg [7:0]  op;        // 0=idle, 1=w_common, 2=r_common, 3=w_s0, 4=r_s0, 5=w_txbuf, 6=r_rxbuf
    reg [15:0] op_addr;
    reg [7:0]  op_len;
    reg        op_read;   // 1=read into buf, 0=write from buf
    reg [7:0]  data_buf [0:127];
    reg [7:0]  data_out;
    reg [7:0]  data_in;
    reg [7:0]  idx;
    reg        op_busy;
    reg        op_done;

    task op_start;
        input [7:0] op_type;
        input [15:0] addr;
        input [7:0] len;
        begin
            op      <= op_type;
            op_addr <= addr;
            op_len  <= len;
            idx     <= 0;
            op_busy <= 1'b1;
            op_done <= 1'b0;
        end
    endtask

    // Low‑level SPI transfer state for an op
    localparam OP_IDLE=0, OP_HDR0=1, OP_HDR1=2, OP_HDR2=3, OP_DATA=4, OP_END=5;
    reg [2:0] op_st;
    reg [7:0] ctrl_byte;

    // TCP state machine
    localparam T_RST=0, T_CFG0=1, T_CFG1=2, T_CFG2=3, T_CFG3=4, T_SOCK0=5, T_LISTEN=6,
               T_POLL=7, T_POLL2=8, T_RECV=9, T_PARSE=10, T_RESP=11, T_SEND=12, T_ACK=13;
    reg [3:0]  t_st;

    // Bookkeeping
    reg [15:0] s0_rx_rsr, s0_rx_rd, s0_tx_wr;
    reg [7:0]  s0_sr;

    // Minimal MBAP/PDU parsing storage
    reg [15:0] mb_tid;     // Transaction ID
    reg [15:0] mb_len;     // Length (PDU + UnitID)
    reg [7:0]  mb_uid;     // Unit ID
    reg [7:0]  mb_fc;      // Function code
    reg [15:0] mb_addr;    // Starting address
    reg [15:0] mb_qty_or_val; // quantity (reads) or value (writes)
    reg [7:0]  resp_len;   // data length to send

    // Simple activity indicator
    always @(posedge clk or posedge rst) begin
        if (rst) link_led <= 1'b0;
        else if (t_st==T_SEND && op_done) link_led <= ~link_led;
    end

    // W5500 op engine
    always @(posedge clk or posedge rst) begin
        if (rst) begin
            cs_n     <= 1'b1;
            spi_start<= 1'b0;
            op_busy  <= 1'b0;
            op_done  <= 1'b0;
            op_st    <= OP_IDLE;
        end else begin
            spi_start <= 1'b0;
            if (!op_busy) begin
                op_done <= 1'b0;
                op_st   <= OP_IDLE;
            end else begin
                case (op_st)
                    OP_IDLE: begin
                        cs_n <= 1'b0;
                        // Determine ctrl byte based on op type
                        case (op)
                            8'd1,8'd2: ctrl_byte <= mk_ctrl(BSB_COMMON, (op==8'd2), 2'b00);
                            8'd3,8'd4: ctrl_byte <= mk_ctrl(BSB_S0_REG, (op==8'd4),  2'b00);
                            8'd5:      ctrl_byte <= mk_ctrl(BSB_S0_TX,  1'b0,       2'b00);
                            8'd6:      ctrl_byte <= mk_ctrl(BSB_S0_RX,  1'b1,       2'b00);
                            default:   ctrl_byte <= 8'h00;
                        endcase
                        op_st <= OP_HDR0;
                    end
                    OP_HDR0: begin
                        if (!spi_busy && !spi_start) begin
                            spi_tx   <= ctrl_byte;
                            spi_start<= 1'b1;
                            op_st    <= OP_HDR1;
                        end
                    end
                    OP_HDR1: begin
                        if (spi_done) begin
                            spi_tx   <= op_addr[15:8];
                            spi_start<= 1'b1;
                            op_st    <= OP_HDR2;
                        end
                    end
                    OP_HDR2: begin
                        if (spi_done) begin
                            spi_tx   <= op_addr[7:0];
                            spi_start<= 1'b1;
                            op_st    <= OP_DATA;
                        end
                    end
                    OP_DATA: begin
                        if (spi_done) begin
                            if (op_len == 0) begin
                                op_st <= OP_END;
                            end else begin
                                // For write ops: tx next byte from data_buf[idx]
                                // For read ops: tx dummy 0x00 and store rx into data_buf[idx]
                                if (op==8'd2 || op==8'd4 || op==8'd6) begin
                                    // reads
                                    spi_tx    <= 8'h00;
                                    spi_start <= 1'b1;
                                    if (spi_done) begin end // wait on next cycle
                                end else begin
                                    // writes
                                    spi_tx    <= data_buf[idx];
                                    spi_start <= 1'b1;
                                end
                                if (spi_done) begin end // consumed above
                            end
                        end else if (!spi_busy && !spi_start && op_len != 0) begin
                            // Latch rx for read ops
                            if (op==8'd2 || op==8'd4 || op==8'd6) begin
                                data_buf[idx] <= spi_rx;
                            end
                            // advance
                            if (op_len != 0) begin
                                op_len <= op_len - 1;
                                idx    <= idx + 1;
                            end
                            if (op_len == 1) begin
                                op_st <= OP_END;
                            end
                        end
                    end
                    OP_END: begin
                        cs_n    <= 1'b1;
                        op_busy <= 1'b0;
                        op_done <= 1'b1;
                        op_st   <= OP_IDLE;
                    end
                endcase
            end
        end
    end

    // Helper procedures
    task w_common; input [15:0] a; input [7:0] n; begin op_start(8'd1,a,n); end endtask
    task r_common; input [15:0] a; input [7:0] n; begin op_start(8'd2,a,n); end endtask
    task w_s0reg;  input [15:0] a; input [7:0] n; begin op_start(8'd3,a,n); end endtask
    task r_s0reg;  input [15:0] a; input [7:0] n; begin op_start(8'd4,a,n); end endtask
    task w_txbuf;  input [15:0] a; input [7:0] n; begin op_start(8'd5,a,n); end endtask
    task r_rxbuf;  input [15:0] a; input [7:0] n; begin op_start(8'd6,a,n); end endtask

    // Reset and configuration state machine
    integer i;
    always @(posedge clk or posedge rst) begin
        if (rst) begin
            t_st        <= T_RST;
            rst_n       <= 1'b0;
            mcp_req_read<= 1'b0; mcp_req_write<=1'b0;
            mcp_olata   <= 8'h00; mcp_olatb <= 8'h00;
            s0_rx_rsr   <= 16'h0000; s0_rx_rd <= 16'h0000; s0_tx_wr <= 16'h0000;
            s0_sr       <= 8'h00;
            for (i=0;i<128;i=i+1) data_buf[i] <= 8'h00;
        end else begin
            mcp_req_read  <= 1'b0;
            mcp_req_write <= 1'b0;

            case (t_st)
                T_RST: begin
                    // hardware reset pulse to W5500 (active low)
                    rst_n <= 1'b0;
                    if (!op_busy) begin
                        // wait few cycles then release
                        rst_n <= 1'b1;
                        t_st  <= T_CFG0;
                    end
                end
                T_CFG0: begin
                    // Write network config: GAR, SUBR, SHAR, SIPR
                    // Prepare data buffer
                    {data_buf[0],data_buf[1],data_buf[2],data_buf[3]} <= {GATEWAY[31:24],GATEWAY[23:16],GATEWAY[15:8],GATEWAY[7:0]};
                    w_common(GAR0, 8'd4);
                    if (op_done) t_st <= T_CFG1;
                end
                T_CFG1: begin
                    {data_buf[0],data_buf[1],data_buf[2],data_buf[3]} <= {SUBNET[31:24],SUBNET[23:16],SUBNET[15:8],SUBNET[7:0]};
                    w_common(SUBR0, 8'd4);
                    if (op_done) t_st <= T_CFG2;
                end
                T_CFG2: begin
                    {data_buf[0],data_buf[1],data_buf[2],data_buf[3],data_buf[4],data_buf[5]} <=
                        {MAC[47:40],MAC[39:32],MAC[31:24],MAC[23:16],MAC[15:8],MAC[7:0]};
                    w_common(SHAR0, 8'd6);
                    if (op_done) t_st <= T_CFG3;
                end
                T_CFG3: begin
                    {data_buf[0],data_buf[1],data_buf[2],data_buf[3]} <= {IPADDR[31:24],IPADDR[23:16],IPADDR[15:8],IPADDR[7:0]};
                    w_common(SIPR0, 8'd4);
                    if (op_done) t_st <= T_SOCK0;
                end
                T_SOCK0: begin
                    // Set S0 RX/TX mem size to 2KB each (value 0x55 => 2KB for S0)
                    data_buf[0] <= 8'h55; w_common(RMSR,8'd1);
                    if (op_done) begin
                        data_buf[0] <= 8'h55; w_common(TMSR,8'd1);
                        if (op_done) begin
                            data_buf[0] <= MR_TCP; w_s0reg(S0_MR, 8'd1);
                            if (op_done) begin
                                data_buf[0] <= 8'h01; data_buf[1] <= 8'hF6; // 502 decimal = 0x01F6
                                w_s0reg(S0_PORT, 8'd2);
                                if (op_done) begin
                                    data_buf[0] <= CR_OPEN; w_s0reg(S0_CR, 8'd1);
                                    if (op_done) t_st <= T_LISTEN;
                                end
                            end
                        end
                    end
                end
                T_LISTEN: begin
                    data_buf[0] <= CR_LISTEN; w_s0reg(S0_CR, 8'd1);
                    if (op_done) t_st <= T_POLL;
                end
                T_POLL: begin
                    // Read socket status
                    r_s0reg(S0_SR, 8'd1);
                    if (op_done) begin
                        s0_sr <= data_buf[0];
                        if (data_buf[0]==SR_ESTABLISHED || data_buf[0]==SR_CLOSE_WAIT) t_st <= T_POLL2;
                        else if (data_buf[0]==SR_LISTEN || data_buf[0]==SR_INIT) t_st <= T_POLL; // stay
                        else if (data_buf[0]==SR_CLOSED) t_st <= T_SOCK0; // reopen
                        else t_st <= T_POLL;
                    end
                end
                T_POLL2: begin
                    // Check RX_RSR for received bytes
                    r_s0reg(S0_RX_RSR0, 8'd2);
                    if (op_done) begin
                        s0_rx_rsr <= {data_buf[0], data_buf[1]};
                        if (s0_rx_rsr >= 7) t_st <= T_RECV; else t_st <= T_POLL;
                    end
                end
                T_RECV: begin
                    // Read RX_RD pointer
                    r_s0reg(S0_RX_RD0, 8'd2);
                    if (op_done) begin
                        s0_rx_rd <= {data_buf[0], data_buf[1]};
                        // Read MBAP header (7 bytes) at RX base + s0_rx_rd
                        r_rxbuf(s0_rx_rd, 8'd7);
                        if (op_done) begin
                            mb_tid   <= {data_buf[0], data_buf[1]};
                            // data_buf[2:3] is protocol id
                            mb_len   <= {data_buf[4], data_buf[5]};
                            mb_uid   <= data_buf[6];
                            // Read PDU next (we cap at 32 bytes)
                            r_rxbuf(s0_rx_rd + 16'd7, (mb_len > 16'd32) ? 8'd32 : mb_len[7:0] - 8'd1);
                            if (op_done) begin
                                mb_fc   <= data_buf[0];
                                // parse FC 0x01/0x02/0x03/0x05
                                mb_addr <= {data_buf[1], data_buf[2]};
                                if (mb_fc==8'h05) begin
                                    mb_qty_or_val <= {data_buf[3], data_buf[4]};
                                end else begin
                                    mb_qty_or_val <= {data_buf[3], data_buf[4]};
                                end
                                // Advance RX_RD pointer by MBAP + PDU length
                                s0_rx_rd <= s0_rx_rd + (16'd7 + (mb_len[15:0]));
                                // write back RX_RD
                                data_buf[0] <= s0_rx_rd[15:8];
                                data_buf[1] <= s0_rx_rd[7:0];
                                w_s0reg(S0_RX_RD0, 8'd2);
                                if (op_done) begin
                                    data_buf[0] <= CR_RECV; w_s0reg(S0_CR, 8'd1);
                                    if (op_done) t_st <= T_PARSE;
                                end
                            end
                        end
                    end
                end
                T_PARSE: begin
                    // Service functions by requesting MCP, then building response
                    if (mb_fc==8'h01 || mb_fc==8'h02) begin
                        // Read coils/discrete inputs
                        mcp_req_read <= 1'b1;
                        if (mcp_rd_valid) begin
                            // Build response: MBAP with same TID, PID=0, LEN=1+1+N, UID same
                            // data_buf used for TX payload (we'll write header+PDU to TX buffer)
                            // Byte count = 2 (GPIOA,B)
                            // Limit qty to 16; starting at 0 means A then B
                            // Prepare response PDU
                            // MBAP will be filled at T_RESP
                            data_buf[7] <= mb_fc;       // PDU start offset 7
                            data_buf[8] <= 8'd2;        // byte count
                            data_buf[9] <= mcp_gpioa;
                            data_buf[10]<= mcp_gpiob;
                            resp_len    <= 8'd5;  // UID(1) + FC(1) + bytecount(1) + 2 data bytes
                            t_st <= T_RESP;
                        end
                    end else if (mb_fc==8'h03) begin
                        // Read holding registers: map two 16-bit regs
                        // Reg0 = {GPIOB, GPIOA}; Reg1 = mirror
                        mcp_req_read <= 1'b1;
                        if (mcp_rd_valid) begin
                            data_buf[7]  <= mb_fc;
                            data_buf[8]  <= 8'd4; // byte count for 2 registers
                            data_buf[9]  <= mcp_gpiob; // high byte of reg0
                            data_buf[10] <= mcp_gpioa; // low byte of reg0
                            data_buf[11] <= mcp_gpiob; // duplicate reg1 (demo)
                            data_buf[12] <= mcp_gpioa;
                            resp_len     <= 8'd7; // UID + FC + bytecount + 4 bytes
                            t_st <= T_RESP;
                        end
                    end else if (mb_fc==8'h05) begin
                        // Write single coil: address [0..15], value 0xFF00=ON, 0x0000=OFF
                        // Update OLAT for outputs; treat GPIOA as outputs (0..7), GPIOB as inputs (ignore writes >7)
                        // Read current outputs first to modify bit
                        mcp_req_read <= 1'b1;
                        if (mcp_rd_valid) begin
                            mcp_olata <= mcp_gpioa;
                            mcp_olatb <= 8'h00; // not used for outputs in this demo
                            // compute new value
                            if (mb_addr[7:0] < 8'd8) begin
                                if (mb_qty_or_val == 16'hFF00) mcp_olata <= mcp_gpioa | (8'h1 << mb_addr[2:0]);
                                else mcp_olata <= mcp_gpioa & ~(8'h1 << mb_addr[2:0]);
                                mcp_req_write <= 1'b1;
                            end
                            if (mcp_wr_done) begin
                                // Echo write request as response (per Modbus spec)
                                data_buf[7]  <= 8'h05;
                                data_buf[8]  <= (mb_addr[15:8]);
                                data_buf[9]  <= (mb_addr[7:0]);
                                data_buf[10] <= (mb_qty_or_val[15:8]);
                                data_buf[11] <= (mb_qty_or_val[7:0]);
                                resp_len     <= 8'd6; // UID + 5 bytes echo
                                t_st <= T_RESP;
                            end
                        end
                    end else begin
                        // Exception: function not supported
                        data_buf[7]  <= (mb_fc | 8'h80);
                        data_buf[8]  <= 8'h01; // ILLEGAL FUNCTION
                        resp_len     <= 8'd3; // UID + FC+0x80 + 1 byte
                        t_st <= T_RESP;
                    end
                end
                T_RESP: begin
                    // Compose MBAP header in data_buf[0..6] and copy PDU already placed starting at [7]
                    // Build MBAP:
                    data_buf[0] <= mb_tid[15:8];
                    data_buf[1] <= mb_tid[7:0];
                    data_buf[2] <= 8'h00;   // Protocol ID high
                    data_buf[3] <= 8'h00;   // Protocol ID low
                    data_buf[4] <= 8'h00;   // Length high (<= 255 for this demo)
                    data_buf[5] <= resp_len; // Length: UID + PDU bytes
                    data_buf[6] <= mb_uid;  // Unit ID

                    // We must write MBAP+PDU to TX buffer at S0_TX_WR
                    // First, read S0_TX_WR
                    r_s0reg(S0_TX_WR0, 8'd2);
                    if (op_done) begin
                        s0_tx_wr <= {data_buf[0], data_buf[1]};
                        // Write payload into TX buffer starting at s0_tx_wr
                        // total bytes = 7 + (resp_len-1) + 1 = 6 + resp_len + 1? Actually MBAP: 7 bytes (UID included)
                        // resp_len is UID+PDU bytes (we placed UID at [6]); So total = 7 + (resp_len - 1)? No:
                        // MBAP (7) already includes UID; PDU starts at [7]; So total bytes = 7 + (resp_len - 1) since UID counted in resp_len.
                        // But we put UID at [6], PDU from [7..]. So the total to send is 6 + resp_len + 1? Let's compute simply:
                        // We'll send (7 + (resp_len - 1)) = (resp_len + 6).
                        // We'll copy bytes 0..(resp_len+6-1)
                        // Copy
                        // Fill contiguous data_buf for write_tx: ensure indices [0..resp_len+6-1] are valid.
                        w_txbuf(s0_tx_wr, (resp_len + 6));
                        if (op_done) begin
                            // Advance TX_WR
                            s0_tx_wr <= s0_tx_wr + (resp_len + 6);
                            data_buf[0] <= s0_tx_wr[15:8];
                            data_buf[1] <= s0_tx_wr[7:0];
                            w_s0reg(S0_TX_WR0, 8'd2);
                            if (op_done) t_st <= T_SEND;
                        end
                    end
                end
                T_SEND: begin
                    data_buf[0] <= CR_SEND; w_s0reg(S0_CR, 8'd1);
                    if (op_done) t_st <= T_ACK;
                end
                T_ACK: begin
                    // Loop back to POLL for next packet
                    t_st <= T_POLL;
                end
            endcase
        end
    end
endmodule

rtl/top.v

Top‑level integration:
– Shares SPI bus between W5500 and MCP23S17; dedicated CS/reset lines.
– Exposes Modbus‑TCP server and maps coils/registers to MCP23S17 ports.
– Uses iCEBreaker net names to align with official PCF.

// rtl/top.v
module top (
    input  wire CLK,            // 12 MHz
    output wire LED_R,
    output wire LED_G,
    output wire LED_B,

    // PMOD1A signals per official icebreaker.pcf naming
    output wire PMOD1A_1, // SPI_SCK
    output wire PMOD1A_2, // SPI_MOSI
    input  wire PMOD1A_3, // SPI_MISO
    output wire PMOD1A_4, // CS_W5500 (n)
    input  wire PMOD1A_5, // W5500_INTn
    output wire PMOD1A_6, // MCP_RSTn (n)
    output wire PMOD1A_7, // CS_MCP (n)
    output wire PMOD1A_8  // W5500_RSTn (n)
);
    wire clk = CLK;
    wire rst = 1'b0; // use power‑on reset or add your own reset synchronizer

    // Shared SPI lines
    wire spi_sck, spi_mosi, spi_miso;
    assign PMOD1A_1 = spi_sck;
    assign PMOD1A_2 = spi_mosi;
    wire   miso_in = PMOD1A_3;

    // Chip selects
    wire cs_w5500_n, cs_mcp_n;
    assign PMOD1A_4 = cs_w5500_n;
    assign PMOD1A_7 = cs_mcp_n;

    // Resets and INT
    wire w5500_rst_n, mcp_rst_n, w5500_int_n;
    assign PMOD1A_8 = w5500_rst_n;
    assign PMOD1A_6 = mcp_rst_n;
    assign w5500_int_n = PMOD1A_5;

    // Status LEDs: indicate link/activity
    reg led_r, led_g, led_b;
    assign LED_R = ~led_r; // active low on iCEBreaker RGB
    assign LED_G = ~led_g;
    assign LED_B = ~led_b;

    // Instantiate MCP23S17 interface (SPI on shared lines)
    wire mcp_sck, mcp_mosi;
    wire mcp_cs_n, mcp_rstn;

    // We'll drive SPI from W5500 engine; to share, we multiplex at top:
    // We'll actually instantiate a single SPI engine in each interface; to share the physical lines,
    // we OR sck/mosi only when their CS is asserted (active low), ensuring only one master drives at a time.
    // This works because only one interface initiates transfers at a time in our schedule.

    // MCP
    wire        mcp_spi_sck, mcp_spi_mosi;
    wire [7:0]  mcp_gpioa, mcp_gpiob;
    wire        mcp_req_read, mcp_rd_valid;
    wire        mcp_req_write, mcp_wr_done;
    reg  [7:0]  mcp_olata, mcp_olatb;

    mcp23s17_if #(.DIV(1)) MCP (
        .clk(clk), .rst(rst),
        .sck(mcp_spi_sck), .mosi(mcp_spi_mosi), .miso(miso_in),
        .cs_n(cs_mcp_n),
        .rst_n(mcp_rst_n),
        .req_read(mcp_req_read),
        .rd_valid(mcp_rd_valid),
        .gpioa(mcp_gpioa),
        .gpiob(mcp_gpiob),
        .req_write(mcp_req_write),
        .olata(mcp_olata),
        .olatb(mcp_olatb),
        .wr_done(mcp_wr_done)
    );

    // W5500
    wire        w_sck, w_mosi;
    wire        w_cs_n, w_rst_n, w_link_led;

    w5500_if #(
        .DIV(1),
        .GATEWAY(32'hC0A83201), // 192.168.50.1
        .SUBNET (32'hFFFFFF00), // 255.255.255.0
        .MAC    (48'h02123456789A),
        .IPADDR (32'hC0A83202)  // 192.168.50.2
    ) WZ (
        .clk(clk), .rst(rst),
        .sck(w_sck), .mosi(w_mosi), .miso(miso_in), .cs_n(cs_w5500_n),
        .rst_n(w5500_rst_n), .int_n(w5500_int_n),
        .mcp_req_read(mcp_req_read),
        .mcp_rd_valid(mcp_rd_valid),
        .mcp_gpioa(mcp_gpioa),
        .mcp_gpiob(mcp_gpiob),
        .mcp_req_write(mcp_req_write),
        .mcp_olata(mcp_olata),
        .mcp_olatb(mcp_olatb),
        .mcp_wr_done(mcp_wr_done),
        .link_led(w_link_led)
    );

    // Wire shared lines: only the active CS drives. Since both SPI engines can toggle their SCK/MOSI,
    // but only the one with CS low should be considered active, we gate outputs.
    assign spi_sck  = (cs_w5500_n==1'b0) ? w_sck  :
                      (cs_mcp_n  ==1'b0) ? mcp_spi_sck : 1'b0;
    assign spi_mosi = (cs_w5500_n==1'b0) ? w_mosi :
                      (cs_mcp_n  ==1'b0) ? mcp_spi_mosi : 1'b0;

    // Simple status LED behavior
    always @(posedge clk) begin
        led_g <= w_link_led; // blink on activity
        led_r <= 1'b0;
        led_b <= 1'b0;
    end
endmodule

Notes:
– The shared SPI multiplexing relies on not scheduling overlapping bus ops; the W5500 FSM controls when it triggers MCP operations. This keeps only one CS active at a time and avoids contention.
– For a production design, instantiate a single SPI master and implement a small arbiter. Here we kept modules concise for clarity.


Build/Flash/Run Commands

Directory layout:
– project/
– rtl/top.v
– rtl/spi_simple.v
– rtl/w5500_if.v
– rtl/mcp23s17_if.v
– constraints/icebreaker.pcf

Commands:

yosys -V           # expect 0.40
nextpnr-ice40 -V   # expect 0.4
icepack -V         # icestorm icepack 0.1
openFPGALoader -V  # expect 0.12

# 1) Get the canonical iCEBreaker PCF (only once)
mkdir -p constraints
curl -L -o constraints/icebreaker.pcf \
  https://raw.githubusercontent.com/icebreaker-fpga/icebreaker-examples/master/constraints/icebreaker.pcf

# 2) Synthesis
mkdir -p build
yosys -p "read_verilog rtl/spi_simple.v rtl/mcp23s17_if.v rtl/w5500_if.v rtl/top.v; synth_ice40 -top top -json build/top.json"

# 3) Place & Route
nextpnr-ice40 --up5k --package sg48 --freq 12 \
  --pcf constraints/icebreaker.pcf \
  --json build/top.json --asc build/top.asc

# 4) Bitstream pack
icepack build/top.asc build/top.bin

# 5) Program board (iCEBreaker)
openFPGALoader -b icebreaker build/top.bin

Ensure the iCEBreaker is connected via USB‑C and recognized.


Step‑by‑Step Validation

1) Physical checks
– Power iCEBreaker via USB. The WIZ850io LEDs should show link when connected to switch/router.
– Ensure MCP23S17 has VDD=3.3 V and RESET pulled high via PMOD1A_6.

2) Network reachability
– Set your host machine to the 192.168.50.0/24 subnet. Example on Linux:
– IP 192.168.50.10/24, gateway 192.168.50.1
– Ping is not supported by W5500 inherently without host IP stack; do not expect ICMP replies.

3) Check TCP port 502 open
– From your host:

nc -vz 192.168.50.2 502
# Expected: Connection to 192.168.50.2 502 port [tcp/*] succeeded!

4) Read coils (0..15) using mbpoll
– Install mbpoll (e.g., via package manager) and run:

mbpoll -m tcp 192.168.50.2 -p 502 -a 1 -t 0 -r 0 -c 16
# -m tcp : Modbus TCP
# -p 502 : port
# -a 1   : Unit ID 1
# -t 0   : data type coils
# -r 0   : starting address 0
# -c 16  : quantity 16
  • Expected: two bytes worth of coils returned. Coils 0..7 map to MCP GPIOA0..7 (configured outputs in this demo) and 8..15 map to MCP GPIOB0..7 (inputs in this demo). If inputs are floating, add pull‑ups/downs or press switches to see changes.

5) Write a single coil (turn on LED on GPIOA0)

# Write Single Coil, address 0, ON (FF00)
mbpoll -m tcp 192.168.50.2 -p 502 -a 1 -t 5 -r 0 1
# Then read back coils:
mbpoll -m tcp 192.168.50.2 -p 502 -a 1 -t 0 -r 0 -c 8
  • Expected: coil 0 set to 1, LED wired to GPIOA0 lights. The gateway echoes the write per Modbus spec.

6) Read holding registers (0..1)

mbpoll -m tcp 192.168.50.2 -p 502 -a 1 -t 3 -r 0 -c 2
  • Expected: Two 16‑bit values. Reg0 is {GPIOB, GPIOA}. Reg1 mirrors Reg0 in this demo.

7) Validate with Python (optional)

python3 -m venv .venv
source .venv/bin/activate
pip install pymodbus==3.6.5
python - << 'PY'
from pymodbus.client import ModbusTcpClient
c = ModbusTcpClient('192.168.50.2', port=502, unit_id=1)
print("Open:", c.connect())
rr = c.read_coils(0, 16)
print("Coils:", rr.bits if rr.isError() is False else rr)
wr = c.write_coil(0, True)
print("Write coil 0:", wr)
rr = c.read_holding_registers(0, 2)
print("Holding:", rr.registers if rr.isError() is False else rr)
c.close()
PY

8) Packet capture with Wireshark
– Capture on your Ethernet interface, filter:

tcp.port == 502
  • Verify MBAP headers: Protocol ID 0x0000, Unit ID 0x01, and PDU content. Confirm responses match requests.

Troubleshooting

  • No link LEDs on WIZ850io:
  • Check 3.3 V and GND continuity to WIZ850io.
  • Verify W5500_RSTn is released high (PMOD1A_8).
  • Ensure RJ45 cable is good and plugged into an active switch/router.
  • Port 502 not open or connection refused:
  • Ensure bitstream programmed successfully.
  • Verify W5500 network config matches your subnet (GATEWAY/SUBNET/IPADDR in top.v).
  • Avoid IP conflicts with other devices.
  • Modbus read returns zeros or errors:
  • Verify MCP23S17 wiring: CS_MCP (PMOD1A_7), SCK/MOSI/MISO routing, RESET high.
  • Confirm that inputs are not floating; add pull‑ups/pull‑downs for stable states.
  • Check that our SPI SCK speed is appropriate; reduce DIV if necessary.
  • Writes to coils don’t change outputs:
  • The demo config sets IODIRA=0x00 (all outputs) and IODIRB=0xFF (all inputs). Only coils 0..7 are driven.
  • Ensure your LED polarity and current‑limit resistors are correct.
  • Sporadic failures / timeouts:
  • Check shared SPI bus integrity; minimize wire length and crosstalk.
  • Confirm only one CS is asserted at a time (logic bug or wiring short can break bus).
  • If your network uses firewalls, allow TCP/502 between host and 192.168.50.2.
  • Build fails at P&R:
  • Confirm nextpnr target matches: –up5k –package sg48.
  • Ensure constraints/icebreaker.pcf is present and net names match top‑level ports.
  • Programming fails:
  • Use: openFPGALoader -b icebreaker build/top.bin
  • On Linux, add udev rules for FTDI if needed or run with sudo for a test.

Improvements

  • SPI master unification:
  • Replace per‑module SPI engines with one shared master and a simple request/ack arbiter for deterministic bus ownership and easier timing analysis.
  • Full Modbus function coverage:
  • Add FC 0x0F (Write Multiple Coils) and 0x10 (Write Multiple Registers), enforcing address and length ranges and proper bit packing.
  • Configurable I/O directions:
  • Implement Modbus holding registers to set MCP23S17 IODIR registers for per‑bit direction control.
  • Debouncing and input filtering:
  • Add configurable debounce filters for discrete inputs.
  • Multiple client handling:
  • Use W5500’s multiple sockets; implement a small connection manager to accept/serve one client at S0 while closing others or serializing access.
  • Dynamic network configuration:
  • Expose IP/MAC/port via compile‑time generics or a simple UDP config channel.
  • Performance tuning:
  • Increase SPI clock (e.g., 12 MHz SCK) after signal integrity validation.
  • Batch RX/TX buffer transfers using larger bursts to reduce overhead.
  • Robust error handling:
  • Parse and clear W5500 interrupts (S0_IR) and handle CLOSE_WAIT by issuing disconnect/close as needed.
  • Test framework:
  • Add automated integration tests with scapy or pymodbus plus golden captures.

Final Checklist

  • Connections
  • PMOD1A_1/2/3 wired to SCK/MOSI/MISO on both WIZ850io and MCP23S17.
  • PMOD1A_4 → WIZ850io SCSn; PMOD1A_7 → MCP23S17 CS.
  • PMOD1A_8 → WIZ850io RSTn; PMOD1A_6 → MCP23S17 RESET (held high).
  • PMOD1A_5 ↔ WIZ850io INTn (optional but recommended).
  • 3.3 V and GND common to both modules and iCEBreaker.
  • Build
  • constraints/icebreaker.pcf downloaded from official repo.
  • yosys/nextpnr/icestorm/openFPGALoader versions verified.
  • Commands executed in order; build/top.bin generated.
  • Flash
  • openFPGALoader -b icebreaker build/top.bin succeeds without error.
  • Network
  • WIZ850io link/activity LEDs normal when Ethernet connected.
  • Subnet configured; host can connect to 192.168.50.2:502.
  • Modbus Validation
  • mbpoll read_coils, write_single_coil, and read_holding_registers succeed.
  • Coils 0..7 control MCP GPIOA outputs; coils 8..15 reflect MCP GPIOB inputs.
  • Observability
  • LED_G toggles on activity (w_link_led bound).
  • Wireshark shows valid MBAP and PDU exchanges on TCP/502.
  • Stability
  • No SPI contention; only one CS active during transactions.
  • No timeouts or unexpected resets during extended testing.

This completes the advanced Modbus‑TCP I/O gateway using iCEBreaker iCE40UP5K + WIZ850io (W5500) + MCP23S17 with an open‑source toolchain.

Find this product and/or books on this topic on Amazon

Go to Amazon

As an Amazon Associate, I earn from qualifying purchases. If you buy through this link, you help keep this project running.

Quick Quiz

Question 1: What is the primary objective of the project described in the article?




Question 2: Which FPGA is used in the project?




Question 3: What communication protocol is implemented in the gateway?




Question 4: What is the function of the MCP23S17 in the project?




Question 5: Which toolchain is used for the project?




Question 6: What is the preferred CLI tool for Modbus testing mentioned in the article?




Question 7: Which Ethernet module is utilized in the project?




Question 8: What type of rights are required on the host machine?




Question 9: What is the purpose of the USB-C cable in the project?




Question 10: Which of the following is NOT a prerequisite for the project?




Carlos Núñez Zorrilla
Carlos Núñez Zorrilla
Electronics & Computer Engineer

Telecommunications Electronics Engineer and Computer Engineer (official degrees in Spain).

Follow me:
Scroll to Top