WiFi CNC Controller — Engineering Reference
Firmware version 1.0.0 — ESP32-S3 based 6-axis CNC motion controller with dual-mode operation: binary protocol (Mach3 plugin / LinuxCNC HAL) and GRBL-compatible G-code interpreter (any standard sender over WiFi telnet or USB serial).
System Architecture
Core Allocation & Task Map
| Task | Priority | Stack | Core | Purpose |
|---|---|---|---|---|
motion_control_task | 20 | 4096 | 1 | Segment execution, state machine |
stepper ISR | ISR | IRAM | 1 | 1 MHz timer, Bresenham stepping |
udp_receive_task | 10 | 4096 | 0 | Binary protocol motion/control |
gcode_exec_task | 8 | 6144 | 0 | G-code parse + plan + emit |
gcode_uart_task | 7 | 3072 | 0 | USB serial G-code input |
gcode_telnet_task | 6 | 4096 | 0 | WiFi telnet server (port 23) |
tcp_server_task | 5 | 4096 | 0 | Binary protocol config/handshake |
wifi_manager | 5 | 4096 | 0 | WiFi STA/AP management |
status_report_task | 3 | 2048 | 0 | UDP status broadcast |
File Map
Green = new files, Yellow = modified files
Stepper Engine (motion/stepper.c)
Hardware timer ISR at 1 MHz resolution. Bresenham multi-axis step distribution with
jerk-limited S-curve velocity profiles (trapezoidal fallback when $40=0).
All state in DRAM for zero-latency ISR access.
Key Data Flow
wcnc_motion_segment_t
→ stepper_load_segment()
→ Compute Bresenham counters, accel/decel boundaries
→ Start GPTimer
→ ISR fires at current_interval (us)
→ Set direction pins
→ Wait dir_setup_us
→ Check probe pin (if WCNC_SEG_FLAG_PROBE)
→ Bresenham: counter += steps[axis], if overflow: step pin HIGH
→ Wait step_pulse_us
→ Step pins LOW
→ Update position[axis]
→ Compute next interval (7-phase S-curve or trapezoidal ramp)
→ Schedule next alarm
S-Curve (Jerk-Limited) Acceleration
When $40 (max jerk) is non-zero, the ISR uses a 7-phase velocity profile
where acceleration ramps up and down smoothly instead of switching instantly:
Trapezoidal: |¯¯¯¯¯| |¯¯¯¯¯| (acceleration)
0 accel cruise decel 0
S-curve: /¯¯¯¯¯\ /¯¯¯¯¯\ (acceleration)
0 ramp const ramp 0
The 7 phases: jerk-up → const-accel → jerk-down → cruise → jerk-down → const-decel → jerk-up. Each jerk ramp is capped to ⅓ of the accel/decel phase to avoid overshooting.
All computation is integer add/subtract/compare using v² kinematic tracking
(speed_sq += current_two_accel). No floating-point or flash function calls
in the ISR — fully IRAM-safe.
| Setting | NVS Key | Default | Effect |
|---|---|---|---|
$40 | jerk_max | 1000 | Max jerk (mm/sec³). 0 = trapezoidal fallback. |
$40=500 for smooth finishing, $40=2000 for fast positioning.
$40=0 disables S-curve entirely (original trapezoidal behaviour).
Probe Detection in ISR
When a segment carries WCNC_SEG_FLAG_PROBE, the ISR checks the probe pin via
gpio_ll_get_level() (direct register read, no function call overhead) on every step tick.
When triggered, motion stops immediately and probe_triggered is set. The G-code interface
reads the stopped position as the probe result.
Step Rate Architecture
The stepper engine uses a single hardware timer (GPTimer) at 1 MHz resolution (1µs ticks). The Bresenham algorithm distributes steps across all active axes within a single ISR call.
Aggregate Rate Limit
CFG_MAX_AGGREGATE_STEP_RATE = 250,000 — this is the ISR firing rate cap,
not a per-axis limit. The minimum timer interval is clamped to 4µs (= 1,000,000 / 250,000).
- Single axis moving alone: Can theoretically reach 250 kHz step rate
- Multiple axes moving simultaneously: The ISR fires at the rate of the dominant (fastest) axis. Other axes receive their steps via Bresenham distribution within the same ISR call. All active axes pulse in parallel — the rate is not divided among axes.
Practical Rate Limits
Each ISR call has fixed overhead from the direction setup and step pulse timing:
| Timing Parameter | NVS Key | Default | Description |
|---|---|---|---|
| Direction Setup | dir_us | 2µs | Delay after setting direction pins before stepping |
| Step Pulse Width | pulse_us | 3µs | Minimum pulse HIGH time for stepper driver |
| Total ISR overhead | 5µs | Minimum time per ISR call (direction + pulse) |
With default timing (5µs overhead per ISR call), the practical maximum step rate is approximately
200 kHz (1/5µs). Reducing pulse_us to 2µs and dir_us to 1µs
would yield ~333 kHz theoretical, but the 4µs minimum interval clamp limits this to 250 kHz.
Per-Axis Rate Clamping
Each axis's max_rate (configured via $110-$115) is individually clamped to
CFG_MAX_AGGREGATE_STEP_RATE at boot:
if (st.max_rate[i] > CFG_MAX_AGGREGATE_STEP_RATE)
st.max_rate[i] = CFG_MAX_AGGREGATE_STEP_RATE;
This prevents any axis from being configured above the hardware-enforced ceiling.
Position Preservation
stepper_estop() stops the timer and disables outputs but never zeros the position counter.
st.position[] always reflects the exact step where motion ceased. This is critical for
E-stop recovery.
Planner Ring Buffer (motion/planner.c)
128-slot SPSC (single-producer, single-consumer) lock-free circular buffer. Producer: Core 0 (protocol handler or G-code planner). Consumer: Core 1 (motion control task).
| Function | Called From | Description |
|---|---|---|
planner_push_segment() | Core 0 | Add segment, blocks if full |
planner_pop_segment() | Core 1 | Consume next segment |
planner_available() | Any | Free slots (for back-pressure) |
planner_capacity() | Any | Total capacity (128) |
planner_is_empty() | Any | Check if buffer empty |
planner_clear() | Core 0 | Discard all segments (E-stop) |
Motion Control Task (motion/motion_control.c)
Core 1 state machine. Pops segments from the ring buffer and loads them into the stepper engine. States: IDLE, RUN, HOLD, JOG, HOMING, PROBING, ALARM, ESTOP.
GPIO & I/O Control (io/gpio_control.c)
| Function | Description |
|---|---|
gpio_control_init() | Load pin assignments from NVS (compile-time defaults as fallback), configure GPIO |
gpio_control_get_probe() | Read probe pin (with inversion) |
gpio_control_get_limit(axis) | Read limit switch for axis |
gpio_control_get_limit_mask() | All limit states as bitmask |
gpio_control_set_spindle(bool) | Enable/disable spindle output |
gpio_control_set_misc_output(n, state) | Set misc output pin |
gpio_control_get_estop() | Read E-stop input |
gpio_control_set_led(bool) | Legacy stub — LED now managed by status_led module |
Supported Boards
| Board | Define | Charge Pump | Misc Out | Notes |
|---|---|---|---|---|
| Waveshare ESP32-S3-Zero | BOARD_ESP32S3_ZERO | No | 0 | Compact, limited GPIO |
| ESP32-S3-DevKitC-1 | BOARD_ESP32S3_DEVKITC | Yes | 2 | Most GPIO, recommended |
| ESP32-WROOM-32 | BOARD_ESP32_WROOM32 | No | 0 | Classic ESP32, input-only GPIOs |
NVS Configuration (persist/nvs_config.c)
Non-volatile storage for all runtime settings. Values persist across power cycles.
Accessible via binary protocol (WCNC_PKT_CONFIG_GET/SET) and GRBL $N=value commands.
Two access methods:
- By NVS key (direct):
nvs_config_get_float("spm_x", 800.0f) - By protocol key (binary):
nvs_config_get_by_protocol_key(WCNC_CFG_STEPS_MM_X, ...) - By GRBL number (G-code):
grbl_setting_set(100, 800.0f)maps to"spm_x"
Runtime Pin Remapping
GPIO pin assignments are stored in NVS and can be changed at runtime without recompiling firmware.
Compile-time defaults from pin_config.h serve as fallback values when no NVS entry exists.
How It Works
- Boot:
stepper_init()andgpio_control_init()read pin assignments from NVS, falling back to compile-timepin_config.hdefaults if no NVS entry exists - Runtime storage: Pins are cached in static variables (
st.step_pins[],s_limit_pins[],s_estop_pin, etc.) and used throughout the firmware - Configuration: Pin assignments can be read/written via the binary protocol (
CONFIG_GET/SETwith keys0x0500-0x0519) or the GUI Pins tab - Reboot required: Pin changes are written to NVS immediately but only take effect after reboot. Reconfiguring GPIOs while the stepper ISR is running would be unsafe.
Pin Configuration Keys (0x0500–0x0519)
| Protocol Key | NVS Key | Description | Board Default |
|---|---|---|---|
0x0500 | p_sx | Step X GPIO | Board-specific |
0x0501 | p_sy | Step Y GPIO | Board-specific |
0x0502 | p_sz | Step Z GPIO | Board-specific |
0x0503 | p_sa | Step A GPIO | Board-specific |
0x0504 | p_sb | Step B GPIO | Board-specific |
0x0505 | p_sc | Step C GPIO | Board-specific |
0x0506 | p_dx | Dir X GPIO | Board-specific |
0x0507 | p_dy | Dir Y GPIO | Board-specific |
0x0508 | p_dz | Dir Z GPIO | Board-specific |
0x0509 | p_da | Dir A GPIO | Board-specific |
0x050A | p_db | Dir B GPIO | Board-specific |
0x050B | p_dc | Dir C GPIO | Board-specific |
0x050C | p_en | Enable GPIO | Board-specific |
0x050D | p_lx | Limit X GPIO | Board-specific |
0x050E | p_ly | Limit Y GPIO | Board-specific |
0x050F | p_lz | Limit Z GPIO | Board-specific |
0x0510 | p_la | Limit A GPIO | Board-specific |
0x0511 | p_lb | Limit B GPIO | Board-specific |
0x0512 | p_lc | Limit C GPIO | Board-specific |
0x0513 | p_prb | Probe GPIO | Board-specific |
0x0514 | p_est | E-Stop GPIO | Board-specific |
0x0515 | p_spn | Spindle GPIO | Board-specific |
0x0516 | p_led | Status LED GPIO | Board-specific |
0x0517 | p_cp | Charge Pump GPIO | Board-specific* |
0x0518 | p_mo0 | Misc Output 0 GPIO | Board-specific* |
0x0519 | p_mo1 | Misc Output 1 GPIO | Board-specific* |
* Charge pump and misc outputs only available on boards that define HAS_CHARGE_PUMP or
MISC_OUTPUT_COUNT > 0 (e.g. ESP32-S3-DevKitC). All pin keys are WCNC_VAL_UINT8 (GPIO number 0–48).
"Pin config 0x05XX updated — reboot required" when a pin key is written.
Reassigning GPIOs while the stepper ISR is active would cause undefined behaviour.
GUI Pin Configuration
The protocol test GUI (tools/protocol_test_gui.py) includes a Pins tab
for reading and writing all 26 pin assignments. The tab shows:
- Stepper pins table: 6 rows (X–C) × 3 columns (Step, Dir, Limit GPIO)
- Single pins: Enable, Probe, E-Stop, Spindle, LED, Charge Pump, Misc Out 0/1
- Read button: fetches current pin config from ESP32
- Write & Save button: sends all pin values to NVS and commits to flash
Network Stack
| Port | Protocol | Direction | Purpose |
|---|---|---|---|
| 58427 | UDP | PC → ESP32 | Motion segments, jog, E-stop, home, I/O |
| 58428 | UDP | ESP32 → PC | Status reports (50ms interval) |
| 58429 | TCP | Bidirectional | Handshake, config get/set, keepalive |
| 23 | TCP (telnet) | Bidirectional | G-code text interface (single client) |
| UART0 | Serial | Bidirectional | G-code text interface (115200 baud) |
Ethernet (W5500) Setup
The Tiggy Pro board supports wired Ethernet via an external W5500 SPI module (such as the USR-ES1 breakout board). When a W5500 module is connected, the firmware automatically uses Ethernet instead of WiFi. If no module is detected at power-on, WiFi starts as normal. All your existing software (Mach3 plugin, LinuxCNC, G-code senders) works identically over Ethernet — the only difference is you connect via a network cable instead of WiFi.
What You Need
- A USR-ES1 or similar W5500 SPI-to-Ethernet module (available for a few pounds on Amazon/eBay/AliExpress)
- 5 jumper wires (female-to-female Dupont)
- A standard Ethernet cable (Cat5e or better)
- A router or switch on your local network
Wiring Diagram
Connect the W5500 module to the ESP32-S3-DevKitC using these 5 wires, plus power:
Pin Summary
| W5500 Pin | ESP32 GPIO | Notes |
|---|---|---|
| MOSI | 45 | SPI data out (ESP32 → W5500) |
| MISO | 46 | SPI data in (W5500 → ESP32) |
| SCLK | 0 | SPI clock |
| INT | 47 | Interrupt (was Misc Input 2, reassigned for Ethernet) |
| CS | — | Tie to GND (always selected) |
| RST | — | Tie to 3.3V (always running) |
| 3.3V | 3V3 | Power supply |
| GND | GND | Ground |
Changing the Pins
The default pins work out of the box with no configuration. If your board uses different GPIOs, open the Protocol Tester (connect via WiFi first), go to the Pins tab, and change the Ethernet pin fields (Eth MOSI, Eth MISO, Eth SCLK, Eth INT). Click Write & Save and reboot the controller.
How It Works
- On power-up, the firmware tries to initialise the W5500 over SPI
- If a W5500 responds, the firmware uses Ethernet and waits up to 5 seconds for a DHCP address
- If Ethernet gets an IP address, WiFi is not started — everything runs over Ethernet
- If no W5500 is found (or no Ethernet cable plugged in), WiFi starts as normal
Nothing else changes. The same TCP/UDP ports, the same protocol, the same software on the PC side. Your Mach3 plugin, LinuxCNC HAL, or G-code sender connects by IP address — it doesn’t matter whether that IP came from WiFi or Ethernet.
I/O Expansion Module Setup
You can use a second ESP32 board as an I/O expansion module to add extra buttons, switches, and relay outputs to your CNC machine. This is useful for pendant controls, external indicator lights, or additional limit switches.
The I/O module runs the same firmware as the main motion controller — you just change one setting to switch it into I/O mode. No separate download or build is needed.
What You Need
- A second ESP32 board (any supported board — even a cheap ESP32-S3-Zero works well for this)
- The same firmware flashed via the Web Flasher
- Both boards on the same WiFi network
Step-by-Step Setup
- Flash the firmware onto the second ESP32 board using the Web Flasher (same as the main controller)
- Connect to the board — it will create a WiFi hotspot called
WiFiCNC-XXXX. Connect your PC to that hotspot, then open the Protocol Tester and connect to192.168.4.1 - Set up WiFi — go to the WiFi tab in the Protocol Tester, enter your network name and password, click Save. The board will reboot and join your network
- Reconnect — connect your PC back to your normal WiFi network. Use the Protocol Tester’s Discover button to find the board’s new IP address
- Switch to I/O Module mode — in the Config tab, find the I/O Module section. Change Device Mode from “Motion Controller” to “I/O Module”
- Set the number of channels — enter how many I/O pins you want to use (e.g. 8 for 8 buttons/outputs)
- Set the direction — the Dir Mask controls which channels are inputs and which
are outputs. Each bit is one channel: 0 = input (button/switch), 1 = output (LED/relay).
For example,
00FFmeans channels 0–7 are outputs, 8–15 are inputs - Assign GPIO pins — in the channel GPIO pin fields, enter the GPIO number
for each channel. For example, if channel 0 is on GPIO 1, enter
1in the first field. Set unused channels to255 - Click Write & Save, then reboot the board
- Configure the Mach3 plugin — in the plugin’s I/O Module tab, tick Enable I/O Module, enter the I/O module’s IP address, and assign functions to each input/output channel
How the I/O Module Communicates
The I/O module uses the same TCP/UDP protocol as the main controller. It identifies itself as an
I/O module during the handshake (the device_mode field in the handshake response is 1
instead of 0). The Mach3 plugin connects to both the main controller and the I/O module using
separate IP addresses.
- Inputs: The I/O module reports button/switch states in its periodic status packets (same as the main controller reports limit switches)
- Outputs: The Mach3 plugin sends output commands to the I/O module (same packet format as spindle/coolant/misc outputs)
G-Code Interpreter
GRBL 1.1-compatible G-code interpreter enabling standalone CNC operation with any standard G-code sender (UGS, CNCjs, bCNC, LaserGRBL). Runs entirely on Core 0.
Data Flow
Parser & Modal State Machine (gcode_parser.c)
Parsing Pipeline
- Strip comments:
(...)inline,;end-of-line - Character-by-character tokenization: extract letter-value pairs
- Dispatch G-codes by integer×10 representation (e.g., G38.2 = 382, G43.1 = 431)
- Modal group conflict detection (error 21 if two G-codes from same group)
- Populate
gcode_block_twith all parsed data
Modal Groups
| Group | Name | Codes | Default |
|---|---|---|---|
| 1 | Motion | G0, G1, G2, G3, G38.2-.5, G80 | G0 |
| 2 | Plane | G17, G18, G19 | G17 (XY) |
| 5 | Feed mode | G93, G94 | G94 |
| 6 | Distance | G90, G91 | G90 (abs) |
| 7 | Units | G20, G21 | G21 (mm) |
| 8 | TLO | G43.1, G49 | G49 (none) |
| 12 | WCS | G54-G59 | G54 |
| 13 | Path control | G61, G64 | G64 (blend) |
| 16 | Arc distance | G90.1, G91.1 | G91.1 (inc) |
Key Data Structures
gcode_block_t — Parsed result from one line
word_bits— Bitmask of which words appeared (X, Y, Z, F, I, J, K, R, etc.)motion_mode— G0/G1/G2/G3/G38.x/G80non_modal_command— G4/G10/G28/G30/G53/G92values[6]— Axis values (X-C),ijk[3],f_value,s_value,r_value,p_value
gcode_state_t — Persistent modal state across lines
- Active modal modes (motion, plane, distance, units, feed mode, path control)
wcs[6][6]— G54-G59 offsets per axisg92_offset[6],g28_position[6],g30_position[6]position[6]— Current machine position (mm)probe_position[6]— Last probe resultfeed_rate(mm/min),spindle_speed(RPM)exact_stop(G61=true, G64=false),path_tolerance(G64 P value)
Look-Ahead Planner (gcode_planner.c)
64-slot circular buffer that sits above the existing 128-slot ring buffer.
Computes junction velocities via forward/backward passes, then emits pre-planned
wcnc_motion_segment_t to the ring buffer. Includes a one-move corner-smoothing
buffer that inserts rounding arcs at sharp corners when G64 P tolerance is active.
Block Addition Pipeline (gcode_planner_line())
- Geometry: Compute delta mm → steps, distance, unit vector, step_event_count
- Axis-limited max speed: For each axis,
limit = max_rate[i] / |unit_vec[i]|. Clamp nominal to minimum. - Axis-limited acceleration: Same approach for acceleration.
- Junction entry speed: Dot product of prev/current unit vectors → cornering speed (see below)
- Backward pass: Walk newest→oldest, ensure kinematic feasibility
- Forward pass: Walk oldest→newest, clamp entry speeds to achievable values
- Adaptive emission: Emit settled blocks based on ring buffer fill level
Junction Velocity — Constant Velocity Vectoring (G64)
G64 Mode (Default — Path Blending)
The machine maintains speed through corners instead of stopping. Junction speed is computed from the angle between consecutive move vectors and a configurable deviation parameter.
Algorithm (GRBL Junction Deviation Method)
cos_theta = dot(prev_unit_vec, current_unit_vec)
sin_half = sqrt(0.5 * (1.0 - cos_theta))
effective_deviation = max(junction_deviation, path_tolerance)
if sin_half > 0.99:
v_junction = 0 // Direction reversal, must stop
elif sin_half < 0.006:
v_junction = INFINITY // Straight line, no speed limit
else:
v_junction = sqrt(accel * effective_deviation * sin_half / (1.0 - sin_half))
v_junction = min(v_junction, prev_nominal, current_nominal)
Configuration
| Setting | NVS Key | Default | Effect |
|---|---|---|---|
$11 | junc_dev | 0.01 mm | Junction deviation tolerance |
G64 Pn | — | 0 mm | Path tolerance (overrides $11 if larger) |
G61 Mode (Exact Stop)
Every move decelerates to zero at its endpoint. max_entry_speed = 0 for all blocks.
Use for precision positioning (drilling, probing).
Adaptive Emission
The emission logic monitors downstream ring buffer fill level to prevent underruns:
| Ring Buffer State | Look-Ahead Depth | Behaviour |
|---|---|---|
| >75% empty | 1 block | Emergency: emit immediately |
| >50% empty | 8 blocks | Reduced planning quality |
| ≤50% empty | 20 blocks | Normal: full velocity optimization |
Corner Smoothing (gcode_planner.c)
When G64 P<tolerance> is active with a non-zero tolerance, the planner
inserts rounding arcs at sharp corners so the machine curves through them instead of
decelerating to the junction speed. This allows much higher sustained feed rates through
complex toolpaths.
Architecture: One-Move Lookahead
A one-move buffer sits between the G-code executor and the planner. Only G1 linear feed moves go through the smoother — G0 rapids, arcs, and probes bypass it and flush the buffer first.
G-code executor
↓
gcode_planner_line_smooth() // Buffers one move, detects corners
↓
gcode_planner_line() // Unchanged, adds to look-ahead buffer
↓
ring buffer → stepper ISR
Corner Detection & Rounding
When two consecutive G1 moves form a corner with turn angle >18°, the smoother:
- Computes the turn angle α from direction vectors
- Calculates rounding radius:
R = tolerance / (1 - cos(α/2)) - Calculates tangent length:
t = R × tan(α/2) - Shortens the first move to an approach point (
corner - t × prev_dir) - Inserts 2–10 arc segments from approach to departure point
- Buffers the remainder of the second move for the next corner check
Rounding Geometry
approach
prev_move ----•
\ ← rounding arc (radius R)
○ (programmed corner)
/
new_move ----•
departure
Deviation = R × (1 - cos(α/2)) = G64 P tolerance
Arc segments use Gram-Schmidt orthogonalization for N-dimensional axis space
Skip Conditions
- G61 (exact stop) active or G64 P0
- Turn angle < 18° (nearly straight) or > 162° (near-reversal)
- Either move shorter than 0.01 mm
- Tangent length exceeds 40% of either move
Example
G64 P0.05 ; 0.05mm path tolerance G1 X100 F600 ; First move G1 Y100 ; 90° corner → R=0.17mm rounding arc inserted ; Machine curves through at near-full speed ; Max deviation from programmed path: 0.05mm
Arc Interpolation (gcode_arcs.c)
Converts G2 (CW) and G3 (CCW) arcs into short line segments. Supports:
- IJK format: Center offset from current position (
G2 X10 Y0 I5 J0) - R format: Radius specification (
G2 X10 Y0 R5) - All planes: G17 (XY), G18 (ZX), G19 (YZ)
- Helical motion: Linear interpolation on the axis perpendicular to the arc plane
- Full circles: When start == end in the arc plane
Segment Count Calculation
theta_per_segment = 2 * acos(1 - tolerance / radius) segments = ceil(|angular_travel| / theta_per_segment) segments = clamp(segments, 1, 2000)
Arc tolerance is configurable via $12 (default 0.002 mm). Smaller tolerance = more segments = smoother arcs.
Last segment always uses exact target coordinates to prevent floating-point drift.
Probing (G38.x)
| G-Code | Direction | Error on No Contact |
|---|---|---|
| G38.2 | Toward workpiece | Yes (alarm 4) |
| G38.3 | Toward workpiece | No |
| G38.4 | Away from workpiece | Yes (alarm 4) |
| G38.5 | Away from workpiece | No |
Probe Sequence
- Flush all pending motion (
gcode_planner_sync) - Wait for stepper to complete
- Push single segment with
WCNC_SEG_FLAG_PROBE | WCNC_SEG_FLAG_LAST - Stepper ISR checks probe pin on every step tick via direct GPIO register read
- On trigger: ISR sets
probe_triggered = true, stops immediately - Record position from stepper counter as probe result
- Probe position queryable via
$#(PRB field) or?status
Jog Commands (gcode_jog.c)
$J=G91 X10 F1000 // Jog X +10mm at 1000mm/min (incremental) $J=G90 X0 Y0 F500 // Jog to X0 Y0 at 500mm/min (absolute) $J=G21 G91 Z-5 F200 // Jog Z -5mm in metric
Supports G90/G91 (distance mode), G20/G21 (units), any axis (X-C), F (feed rate required). Jog moves cancel on feed hold.
GRBL Settings (grbl_settings.c)
Maps GRBL $N=value commands to the NVS configuration system with automatic unit conversion.
| $N | NVS Key | Description | Conversion |
|---|---|---|---|
| $0 | pulse_us | Step pulse time (us) | None |
| $1 | idle_ms | Step idle delay (ms) | None |
| $2 | inv_step | Step port invert mask | None |
| $3 | inv_dir | Dir port invert mask | None |
| $5 | inv_lim | Limit pin invert mask | None |
| $6 | inv_prb | Probe pin invert | None |
| $11 | junc_dev | Junction deviation (mm) | None |
| $12 | arc_tol | Arc tolerance (mm) | None |
| $23 | hm_dir | Homing dir invert mask | None |
| $24 | hm_feed | Homing feed (mm/min) | mm/min → steps/sec |
| $25 | hm_seek | Homing seek (mm/min) | mm/min → steps/sec |
| $27 | hm_pull | Homing pull-off (mm) | mm → steps |
| $100-$105 | spm_x..spm_c | Steps/mm per axis | None (float) |
| $110-$115 | rate_x..rate_c | Max rate (mm/min) | mm/min → steps/sec |
| $120-$125 | acc_x..acc_c | Accel (mm/sec²) | mm/sec² → steps/sec² |
| $130-$132 | trvl_x..trvl_z | Max travel (mm) | None |
| $40 | jerk_max | Max jerk (mm/sec³) | None (float). 0 = trapezoidal. |
Real-Time Commands
These bytes are detected in the raw byte stream and handled immediately (not queued):
| Byte | Character | Action |
|---|---|---|
0x3F | ? | Send GRBL-format status report |
0x21 | ! | Feed hold — controlled deceleration to stop |
0x7E | ~ | Cycle start / resume from hold |
0x18 | Ctrl-X | Soft reset with full position preservation |
Soft Reset Sequence (Ctrl-X)
motion_estop()— stops steppers, position preserved in countergcode_planner_clear()— discards look-ahead blocks, position NOT zeroedplanner_clear()— discards ring buffer segmentsmotion_reset()— state → IDLEgcode_planner_sync_position()— reads actual stepper position- Parser re-initialized to defaults (G54, G17, G90, G21, G64), position preserved
- Line queue flushed, welcome message sent
Status Report Format
<Idle|MPos:0.000,0.000,0.000,0.000,0.000,0.000|FS:0,0|Bf:120,45> <Run|MPos:35.123,20.456,-5.000,0.000,0.000,0.000|FS:600,12000|Bf:98,32|WCO:10.000,5.000,0.000>
| Field | Description | Source |
|---|---|---|
| State | Idle, Run, Hold:0, Jog, Home, Alarm, Check | motion_get_state() |
| MPos | Machine position in mm (always authoritative) | stepper_get_position() / steps_per_mm |
| FS | Feed rate (mm/min), spindle speed (RPM) | stepper_get_feed_rate() |
| Bf | Ring buffer free, look-ahead buffer free | planner_available(), gcode_planner_available() |
| WCO | Work coordinate offset (sent every 10th query) | s_state.wcs[] + g92_offset[] |
Transports
Telnet (gcode_telnet.c) — Port 23
- Single-client TCP server
- Sends GRBL welcome on connect:
Grbl 1.1h ['$' for help]\r\n - 100ms receive timeout for periodic disconnect checking
- Telnet IAC sequences (0xFF) automatically skipped
- Backspace/delete support
- Sets output callback to
send(sock, ...)
UART (gcode_uart.c) — USB Serial
- UART0 at 115200 baud (TX=GPIO43, RX=GPIO44 on S3)
- Same byte processing logic as telnet
- Sets output callback to
uart_write_bytes() - Always active (no connect/disconnect)
Binary Protocol Specification
Magic: 0x574D4333 ("WMC3"), Protocol version: 1, CRC-16/CCITT checksum.
Packet Header (18 bytes)
typedef struct {
uint32_t magic; // 0x574D4333
uint8_t version; // 1
uint8_t packet_type; // WCNC_PKT_*
uint16_t payload_length; // Bytes after header
uint32_t sequence; // Incrementing counter
uint32_t timestamp; // Milliseconds
uint16_t checksum; // CRC-16/CCITT over entire packet
} wcnc_header_t;
Motion Segment Format
typedef struct {
int32_t steps[6]; // Step count per axis (signed)
uint32_t duration_us; // Segment duration (unused by stepper)
uint32_t entry_speed_sqr; // Entry speed squared / 1000
uint32_t exit_speed_sqr; // Exit speed squared / 1000
uint32_t acceleration; // Acceleration * 100 (steps/sec²)
uint16_t segment_id; // Tracking ID
uint8_t flags; // WCNC_SEG_FLAG_*
} wcnc_motion_segment_t;
Segment Flags
| Flag | Value | Meaning |
|---|---|---|
WCNC_SEG_FLAG_RAPID | 0x01 | Rapid traverse (G0) |
WCNC_SEG_FLAG_LAST | 0x02 | Last segment in sequence |
WCNC_SEG_FLAG_PROBE | 0x04 | Probe move (check probe pin) |
WCNC_SEG_FLAG_EXACT_STOP | 0x08 | Decel to zero at end |
IO Control Packet (PC → ESP32, UDP)
Controls spindle, coolant, and misc outputs. Sent via UDP alongside motion packets. The ESP32 stores these states and reports them back in the status report (ground truth).
typedef struct {
wcnc_header_t header;
uint8_t misc_outputs; // Bitmask: bit 0..4 misc output states
uint8_t spindle_state; // 0=off, 1=CW, 2=CCW
uint16_t spindle_rpm; // Target RPM (0..max_rpm)
uint8_t coolant_state; // bit 0=flood, bit 1=mist
uint8_t reserved[3];
} wcnc_io_control_packet_t; // Total: 26 bytes
Mach3 Plugin: Misc Output Triggers
Misc outputs (EXTACT1–5) are controlled via G-code or the Mach3 UI.
The plugin activates Engine->OutSigs[EXTACT1..5].active = true at init
so Mach3 processes these commands.
| G-code | Type | Effect |
|---|---|---|
M62 P0 | Synced with motion | Turn ON misc output 1 (EXTACT1) |
M63 P0 | Synced with motion | Turn OFF misc output 1 (EXTACT1) |
M64 P0 | Immediate | Turn ON misc output 1 (EXTACT1) |
M65 P0 | Immediate | Turn OFF misc output 1 (EXTACT1) |
| P parameter is 0-indexed: P0=Misc1, P1=Misc2, P2=Misc3, P3=Misc4, P4=Misc5 | ||
M62/M63 are synchronized with motion (queued in the trajectory buffer). M64/M65 take effect immediately. Both result in an I/O control packet being sent to the controller firmware.
Status Report Extended Fields (v1.1)
Offset 46–49 of the status report payload (total 50 bytes):
| Field | Offset | Type | Description |
|---|---|---|---|
misc_outputs | 46 | u8 | Bitmask of active misc outputs |
misc_inputs | 47 | u8 | Bitmask of misc input states |
spindle_state | 48 | u8 | 0=off, 1=CW, 2=CCW (from last IO control) |
coolant_state | 49 | u8 | bit 0=flood, bit 1=mist (from last IO control) |
Engine->SpindleCW can contain non-boolean values (e.g. 7).
Status LED Module (io/status_led.c)
Drives the onboard LED with connection/state indication. Supports WS2812 RGB LEDs on ESP32-S3 boards via the RMT peripheral.
| State | WS2812 (S3 boards) | Plain LED (WROOM-32) |
|---|---|---|
| Disconnected (no host) | Red, slow blink | Off |
| Connected, idle | Blue, solid | On, solid |
| Connected, running | Green, solid | On, slow blink |
| Alarm / E-stop | Yellow, fast blink | On, fast blink |
Board LED pins: S3-Zero = GPIO 21, S3-DevKitC = GPIO 48, WROOM-32 = GPIO 2. Colours are intentionally dim (20/255 brightness) to avoid distraction.
Binary / G-Code Coexistence
Both the binary protocol (Mach3/LinuxCNC) and G-code interpreter share the same planner ring buffer
via planner_push_segment(). They are mutually exclusive at the motion level:
Preemption Mechanism
- When binary protocol receives
PKT_MOTION_SEGMENT, it callsgcode_planner_preempt() - This sets
s_planner.preempted = true - The G-code look-ahead planner checks this flag before every
planner_push_segment()call and pauses emission - Un-emitted look-ahead blocks are retained — no data loss
- When binary protocol sends
PKT_RESET, it callsgcode_planner_release() - G-code planner resumes emission
Critical Behaviour: Constant Velocity Vectoring
The #1 requirement for quality CNC motion. Without it, the machine stops between every G1 move, producing faceted surfaces and slow cycle times.
How It Works
When G64 is active (default), the planner computes a non-zero junction speed for every corner. The stepper never decelerates to zero unless:
- Direction reversal on any axis (must stop)
- Junction angle too sharp (unless corner smoothing inserts a rounding arc)
- G61 exact stop mode is active
- End of program (M2/M30)
Example: 90-Degree Corner
G64 P0.01 ; Path blending, 0.01mm tolerance G1 X100 F600 ; Move X at 600mm/min G1 Y100 ; 90-degree turn to Y ; Junction speed: ~30mm/min (computed from deviation) ; Machine rounds the corner smoothly
G61 ; Exact stop mode G1 X100 F600 ; Move X at 600mm/min G1 Y100 ; Full stop at corner, then accelerate to Y ; Junction speed: 0mm/min (exact stop)
Critical Behaviour: Buffer Underrun Recovery
If the ring buffer runs dry (WiFi dropout, sender stall, heavy computation):
- Motion control task transitions to IDLE (existing behaviour)
- Position is preserved — stepper position counter is always accurate
- When new segments arrive, motion_control_task pops and resumes RUN — seamless
planner->underrun_countincrements for diagnostics- Adaptive emission kicks in: look-ahead depth reduces to 1 to feed buffer ASAP
Critical Behaviour: E-Stop Position Preservation
This solves the Mach3 + SmoothStepper problem where E-stop loses position sync and the job can never resume.
E-Stop Recovery Workflow
1. E-stop triggered → stepper_estop(): stops timer, disables outputs → position[] PRESERVED (not zeroed) → state → ESTOP 2. User fixes issue, sends Reset (Ctrl-X or PKT_RESET) → gcode_planner_clear(): discards look-ahead, position untouched → planner_clear(): discards ring buffer → motion_reset(): state → IDLE → gcode_planner_sync_position(): reads actual stepper position 3. Query position → "?" returns: <Idle|MPos:35.000,20.000,-5.000,...> → This IS the real physical position where the machine stopped 4. Resume → G-code sender reads MPos, knows exact position → Can re-home, continue from known position, or restart job → No phantom position drift, no lost steps in the controller
Critical Behaviour: Comms/Motion Isolation
- Core 0: All comms (WiFi, telnet, UART, UDP, TCP, G-code processing)
- Core 1: All motion (stepper ISR, motion control task) — never interrupted by WiFi
- Stepper ISR in IRAM: No flash access, no cache misses
- Direct GPIO register writes: Sub-microsecond pin toggling via
gpio_ll_set_level() - Lock-free ring buffer: No mutexes between cores
- Pre-buffered operation: 128-slot ring buffer = ~2-5 seconds of buffered motion. WiFi glitch for 100ms is invisible.
- No allocations in motion path: All buffers statically allocated
Building & Flashing
Prerequisites
- ESP-IDF v5.x (tested with 5.1+)
- Python 3.x (for ESP-IDF tools)
Board Selection
The board define controls which pin assignments are loaded from pin_config.h at compile time.
It must be set in the build configuration for whichever build system you use:
PlatformIO (recommended)
Edit firmware/platformio.ini, change the -DBOARD_* flag in build_flags:
build_flags =
-DBOARD_ESP32S3_ZERO ; ← change this line
-I../../protocol
ESP-IDF (idf.py)
Auto-detected from IDF target in pin_config.h (S3 → DevKitC, ESP32 → WROOM32).
Override with a cmake define if needed:
idf.py build -DBOARD_ESP32S3_ZERO
Available Boards
| Define | Board | Notes |
|---|---|---|
BOARD_ESP32S3_ZERO | Waveshare ESP32-S3-Zero | Compact, limited GPIO, no charge pump |
BOARD_ESP32S3_DEVKITC | ESP32-S3-DevKitC-1 | Most GPIO, charge pump + 2 misc outputs |
BOARD_ESP32_WROOM32 | ESP32-WROOM-32 | Classic ESP32, input-only GPIOs |
Build & Flash
PlatformIO
cd firmware pio run # Build pio run -t upload # Flash pio device monitor # Serial monitor pio run -t upload -t monitor # All in one
ESP-IDF
cd firmware idf.py set-target esp32s3 idf.py build idf.py -p COMx flash monitor
Connecting G-Code Senders
UGS (Universal G-code Sender)
- Connection type: Serial
- Port:
socket://<ESP32_IP>:23 - Firmware: GRBL
- Click Connect
CNCjs
- Connection: Serial port
- Port:
socket://<ESP32_IP>:23 - Controller type: Grbl
bCNC
- Port:
socket://<ESP32_IP>:23 - Controller: GRBL1
Serial Terminal (direct USB)
- Connect USB cable to ESP32
- Open terminal at 115200 baud, 8N1
- Type G-code commands directly
Protocol Test GUI (binary protocol)
cd tools python protocol_test_gui.py
Enter the ESP32's IP address and click Connect. Uses the binary protocol on UDP/TCP ports.
Testing Procedures
Basic Connectivity
telnet <ESP32_IP> 23 # Should see: Grbl 1.1h ['$' for help] ? # Should see: <Idle|MPos:0.000,0.000,0.000,...> $$ # Should see all settings dumped
Motion Test
G21 ; Set mm mode G90 ; Absolute positioning G64 P0.01 ; Path blending with 0.01mm tolerance G1 X10 F600 ; Linear move 10mm at 600mm/min G1 Y10 ; Should maintain speed through corner G1 X0 Y0 ; Return to origin ? ; Verify position back at 0,0,0
Arc Test
G2 X10 Y0 I5 J0 F600 ; CW semicircle G3 X0 Y0 I-5 J0 F600 ; CCW semicircle back
E-Stop Recovery Test
G1 X100 F600 ; Start long move ; During motion: send Ctrl-X (0x18) ? ; Check MPos — should show actual stopped position (e.g. X35.123) G1 X0 F600 ; Return to zero from actual position ? ; Verify X0.000
Probe Test
G38.2 Z-10 F100 ; Probe toward, expect contact $# ; Check PRB position ? ; Verify stopped position matches probe result
GRBL Command Reference
| Command | Description |
|---|---|
$$ | Dump all settings |
$# | Dump coordinate offsets (G54-G59, G28, G30, G92, PRB) |
$G | Dump active modal state |
$I | Build info |
$H | Run homing cycle (all axes) |
$X | Kill alarm / unlock |
$J=... | Jog command (e.g. $J=G91 X10 F1000) |
$N=value | Set setting N (e.g. $100=800) |
$N | Query setting N |
Supported G/M Codes
G-Codes
| Code | Group | Description |
|---|---|---|
| G0 | Motion | Rapid traverse |
| G1 | Motion | Linear interpolation |
| G2 | Motion | CW arc (IJK or R format) |
| G3 | Motion | CCW arc (IJK or R format) |
| G4 | Non-modal | Dwell (P seconds) |
| G10 L2 | Non-modal | Set WCS offset |
| G10 L20 | Non-modal | Set WCS from current position |
| G17 | Plane | XY plane (default) |
| G18 | Plane | ZX plane |
| G19 | Plane | YZ plane |
| G20 | Units | Inches mode |
| G21 | Units | Millimeter mode (default) |
| G28 | Non-modal | Return to G28.1 stored position |
| G28.1 | Non-modal | Store current position for G28 |
| G30 | Non-modal | Return to G30.1 stored position |
| G30.1 | Non-modal | Store current position for G30 |
| G38.2 | Motion | Probe toward, error on no contact |
| G38.3 | Motion | Probe toward, no error |
| G38.4 | Motion | Probe away, error on no contact |
| G38.5 | Motion | Probe away, no error |
| G40 | Cutter comp | Cancel cutter compensation (no-op, Mach3 compat) |
| G43 | TLO | Tool length offset from tool table (H word selects tool) |
| G43.1 | TLO | Dynamic tool length offset |
| G49 | TLO | Cancel tool length offset |
| G53 | Non-modal | Move in machine coordinates |
| G54-G59 | WCS | Select work coordinate system |
| G61 | Path | Exact stop mode |
| G64 | Path | Constant velocity / path blending (default) |
| G80 | Motion | Cancel canned cycle |
| G90 | Distance | Absolute mode (default) |
| G91 | Distance | Incremental mode |
| G90.1 | Arc dist | Absolute arc centres |
| G91.1 | Arc dist | Incremental arc centres (default) |
| G92 | Non-modal | Set coordinate offset |
| G92.1 | Non-modal | Clear G92 offset |
| G93 | Feed mode | Inverse time feed mode |
| G94 | Feed mode | Units per minute (default) |
M-Codes
| Code | Description |
|---|---|
| M0 | Program pause (wait for cycle start ~) |
| M1 | Optional stop |
| M2 | Program end |
| M3 | Spindle CW |
| M4 | Spindle CCW |
| M5 | Spindle stop |
| M6 | Tool change (flushes motion, logs tool number) |
| M7 | Mist coolant on |
| M8 | Flood coolant on |
| M9 | All coolant off |
| M30 | Program end and rewind |
| M62 Pn | Turn ON misc output n (synced with motion), P0=Misc1 .. P4=Misc5 |
| M63 Pn | Turn OFF misc output n (synced with motion) |
| M64 Pn | Turn ON misc output n (immediate) |
| M65 Pn | Turn OFF misc output n (immediate) |
NVS Config Key Reference
| NVS Key | Type | Default | Description |
|---|---|---|---|
pulse_us | u16 | 3 | Step pulse width (us) |
dir_us | u16 | 2 | Dir setup time (us) |
idle_ms | u16 | 255 | Stepper idle delay (ms) |
spm_x..c | float | 800.0 | Steps per mm per axis |
rate_x..c | u32 | 20000 | Max rate (steps/sec) |
acc_x..c | u32 | 5000 | Acceleration (steps/sec²) |
inv_step | u8 | 0x00 | Step pin invert mask |
inv_dir | u8 | 0x00 | Dir pin invert mask |
inv_en | u8 | 0x00 | Enable pin invert |
inv_lim | u8 | 0x3F | Limit pin invert mask |
inv_hom | u8 | 0x3F | Home pin invert mask |
inv_est | u8 | 0x00 | E-stop pin invert |
inv_prb | u8 | 0x00 | Probe pin invert |
hm_dir | u8 | 0x00 | Homing direction mask |
hm_seek | u32 | 5000 | Homing seek rate (steps/sec) |
hm_feed | u32 | 500 | Homing feed rate (steps/sec) |
hm_pull | u32 | 100 | Homing pulloff (steps) |
junc_dev | float | 0.01 | Junction deviation (mm) |
arc_tol | float | 0.002 | Arc tolerance (mm) |
jerk_max | float | 1000.0 | Max jerk (mm/sec³), 0=trapezoidal |
trvl_x..z | float | 200.0 | Max travel per axis (mm) |
| Pin Assignments (0x0500–0x0519) — require reboot | |||
p_sx..p_sc | u8 | Board-specific | Step GPIO per axis (X–C) |
p_dx..p_dc | u8 | Board-specific | Dir GPIO per axis (X–C) |
p_en | u8 | Board-specific | Stepper enable GPIO |
p_lx..p_lc | u8 | Board-specific | Limit switch GPIO per axis (X–C) |
p_prb | u8 | Board-specific | Probe input GPIO |
p_est | u8 | Board-specific | E-Stop input GPIO |
p_spn | u8 | Board-specific | Spindle enable GPIO |
p_led | u8 | Board-specific | Status LED GPIO |
p_cp | u8 | Board-specific | Charge pump GPIO (if available) |
p_mo0, p_mo1 | u8 | Board-specific | Misc output GPIOs (if available) |
Memory Budget
| Component | Size | Location |
|---|---|---|
| Planner ring buffer (128 × 52B) | 6656 B | Static (BSS) |
| Look-ahead buffer (64 × 120B) | 7680 B | Static (BSS) |
| Line queue (8 × 260B) | 2080 B | FreeRTOS heap |
| Modal state + WCS offsets | ~424 B | Static (BSS) |
| Telnet + UART buffers | ~1536 B | Stack + static |
| GRBL settings cache + scratch | ~512 B | Stack |
| Stepper state (DRAM) | ~512 B | DRAM (ISR-accessible) |
| S-curve phase state | ~64 B | DRAM (ISR-accessible) |
| Corner smooth buffer (6 floats + flags) | ~32 B | Static (BSS) |
| Total G-code allocation | ~13 KB | |
| Total firmware RAM: 48 KB / 320 KB (14.7%) | ||
WiFi CNC Controller — Engineering Reference — Generated February 2026