The ESP's homed flag survives bbctrl restarts (since the ESP itself
stays powered). Host state, on the other hand, gets reset to zero on
boot - State.reset zeros ap and offset_a. Trusting the ESP's homed
flag in that situation made gplan think A was homed at machine-coord 0
while physically the axis was at 134, which then rejected any move
to the bottom (G1 A-134) as 'less than minimum soft limit 0'.
Send UNHOME (new auxcnc verb that just clears g_homed without
moving) on every host connect. The user has to re-home explicitly,
which goes through the proper Mach.home path that sets up the
offset and gplan position consistently.
Falls back to HOMED? if the firmware doesn't know UNHOME, so older
auxcnc builds keep their previous behaviour.
State.reset extended to also clear motor 4's homed flags
(<motor>homed and <motor>h) so the synthetic external-axis motor
gets reset alongside the real AVR motors.
Soft limits in machine coords (min_w/max_w from aux.json) were only
checked by gplan. UI jog/move endpoints went through ExternalAxis
directly without any check, so the W+ button at home would happily
push past max_w into a physical crash.
Add _check_soft_limit(target_abs_mm) called by both motion paths:
the synchronous execute_to_mm (UI) and the non-blocking
enqueue_target_mm (planner). Boundaries inclusive within a 1e-4
epsilon for floating-point round-trip stability. Skipped when the
axis isn't homed, matching the standard bbctrl convention that
soft limits are gated by homing state. Skipped when max <= min
(disabled).
Tested locally:
- pre-home: 200mm allowed (jog-out-of-trouble path)
- post-home: 0 and 134 (boundaries) accepted
- post-home: 135 and -1 rejected with clear error
- 134.00005 accepted (within epsilon), 134.001 rejected
- enqueue path also rejects, propagating up through Planner.next()
- max==min config skips check
Three changes that together implement option (b) home semantics:
1. Mach.home for the external axis: replace G28.3 with explicit
AVR position sync (Cmd.set_axis) + planner abs sync
(position_change) + G92 a0 (set user-coord origin to current
physical position, computing offset = home_position_mm).
G28.3 was wrong: it preserves the current user-coord position
and adjusts the offset to bridge to the new abs. After a move
away from home and a re-home, the offset accumulates
(134 -> 268 -> ...). G92 a0 with a freshly-synced abs always
produces offset = home_position_mm regardless of prior state.
2. Planner.__encode: stop stripping the external axis target from
the AVR line. The AVR has no motor mapped to A so it steps no
motor, but exec_move_to_target updates ex.position[A] which
gets reported back as ap. Leaving A in the AVR target keeps
state.ap consistent with gplan's idea of A; stripping it left
ex.position[A] stale and clobbered ExternalAxis's state.ap on
the next status report.
Side benefit: removes the special-case empty-string return for
pure external moves; every line block follows the same path now.
3. ExternalAxis.enqueue_target_mm: stop writing to state.<axis>p
from the planner hot path. The AVR's status reports drive it
instead, which avoids DRO jitter (jump to target then snap back
to intermediate values as the trapezoid runs). _pos_mm internal
mirror is still updated for delta computation.
Re-verified with the integration smoke test in tmp/20260503_option_b/:
home/move-down/move-up/re-home/home-from-bottom all produce the
expected DRO position values (0 at home, -134 at bottom).
Big-bang refactor of the W-axis integration. The auxcnc ESP stepper
is now exposed to the bbctrl planner (camotics gplan) as a virtual
A axis with no AVR motor mapping. gplan parses gcode for A natively,
applies soft limits, units, accel ramping and S-curve trajectories.
Line blocks with A motion are intercepted in Planner.__encode and
forked to the ESP via ExternalAxis on a worker thread; the residual
XYZ motion goes to the AVR as before.
This replaces the previous (MSG,HOOK:aux:N) side-channel: gcode
authors now write G1 A50 F1000 (or G28 A0 to home) and the planner
handles it the same way it handles X/Y/Z.
## Architecture
The AVR has 4 motor channels (0-3, all assigned to X/Y/Y/Z on
Onefinity). Looking at the AVR source, an axis with no motor
mapping is fully accepted: line blocks with that axis target update
ex.position[axis] in exec.c, but no motor steps because
motor_get_axis(motor)==axis returns -1. The AVR reports 'p' for
all 6 axes regardless. So we expose A to State as a synthetic
motor (index 4, host-only), populated from aux.json with full
kinematic config (vm/am/jm/tn/tm). State.find_motor and the
snapshot projection now walk 0..4. gplan sees A as a real axis.
## New module: ExternalAxis
- Registers synthetic motor 4 with vm/am/jm/tn/tm so
State.find_motor('a') returns 4 and gplan picks up
soft limits + kinematics.
- Worker thread drains a target queue so ESP RPCs (which can
take seconds) never block the bbctrl ioloop.
- execute_to_mm: synchronous, used by HTTP endpoints.
- enqueue_target_mm: non-blocking, used by Planner.__encode.
- home(): runs ESP cycle, syncs <axis>p and <axis>_homed.
- abort(): drains queue.
## Planner
- __encode splits external-axis target out of line blocks.
- Pure A move -> emits id-sync only (planner advances cleanly).
- Mixed XYZ + A -> AVR runs XYZ trapezoid concurrent with the
ESP move (v1 accepts the slight desync; users wanting strict
sequencing put A on its own gcode line).
- _<axis>_homed for the synthetic motor mirrors into State only.
- Planner.reset drains the worker queue and forces resync.
## Mach
- Mach.home(axis='a') routes through ext.home() instead of the
standard G28.2/G38.6 latch sequence (which doesn't apply to an
ESP-driven axis), then issues G28.3 a<home> to sync gplan.
- Mach.unhome strips the AVR path for A.
- Mach.stop / E-stop drain the external-axis worker queue.
- Mach.jog strips A so the AVR doesn't see it (continuous-rate
jogging not supported on ESP yet; use /api/aux/jog instead).
## State
- find_motor walks 0..4 (synthetic motor 4 lives in vars).
- snapshot projection includes motor 4 so 4tn -> a_tn etc.
- get_axis_vector picks up motor-4 values without changes.
## AuxAxis
- Adds set_state_observer hook so ExternalAxis sees homed-flag
changes after homing/boot-banner.
- DEFAULTS now include axis_letter, max_velocity_m_per_min,
max_accel_km_per_min2, max_jerk_km_per_min3 in user-facing
motor-config units (m/min, km/min^2, km/min^3) matching the
onefinity per-motor convention.
## AuxPreprocessor
- Drops W-token rewriting entirely. M100..M103 ATC mapping kept.
- W tokens in legacy gcode now warn (once per file) instead of
being rewritten. Migration: replace W with A.
## Hooks
- aux/aux_rel/aux_setzero hooks retired. aux_home kept as a
legacy alias routing to ext.home() for older preprocessed
gcode. ATC hooks (droptool/grabtool/release/clamp) unchanged.
- E-stop now drains the external-axis worker queue.
## Web.py
- /api/aux/{home,jog,move} now route through ExternalAxis when
available so DRO and gplan position stay in sync.
## UI (axis-vars.js + control-view.pug)
- _get_motor_id and _check_is_enabled fall back to motor index 4
so the standard A column in the DRO renders state for the
ESP-driven axis (with full offset / set-position / per-axis
home support).
- Legacy W row is gated on !a.enabled - shown only for installs
that haven't migrated.
- WAxisSettings.svelte exposes the new max_velocity_m_per_min /
max_accel_km_per_min2 / max_jerk_km_per_min3 fields and an
axis_letter selector for picking A/B/C.
## Open follow-ups (validate on hardware)
- Q1: gplan soft-limit enforcement for A with min/max set.
Easy smoke test: max_w=50, MDI G1 A100, expect rejection.
- Q2: AVR behaviour with a target dict containing A values for
a motorless axis. Read of exec.c suggests it's safe; needs a
smoke test (no motor faults, no unexpected step counts).
- Q3: pause/resume mid-A-move semantics. ESP doesn't honour
bbctrl pauses; ext.abort drains the queue but a move-in-flight
runs to completion. Acceptable for v1; v2 could add a synced
pause.
Map four user-defined M-codes to the existing ATC hooks:
M100 DROPTOOL -> (MSG,HOOK:droptool:)
M101 GRABTOOL -> (MSG,HOOK:grabtool:)
M102 RELEASE -> (MSG,HOOK:release:)
M103 CLAMP -> (MSG,HOOK🗜️)
M100-M103 are in LinuxCNC/Buildbotics user-defined range so the
planner won't error on the raw codes if the preprocessor is bypassed.
Stripped from the residual line and replaced with the hook line.
Order is left-to-right; multiple ATC codes per line and ATC+W on
the same line both work (M100 W10 -> drop then move to W=10).
The file scanner (file_uses_aux, formerly file_uses_w) now wakes
up for either W tokens or ATC M-codes; backwards-compat alias kept.
MDI rewrite (Mach._rewrite_w_mdi) updated likewise.
Tested locally with mixed ATC/W gcode in tmp/20260501_atc_mcodes.
Adds atc_droptool/atc_grabtool/atc_release/atc_clamp wrappers in
AuxAxis (each just an RPC waiting on the matching terminal reply
line from the firmware), and registers them as internal hook
handlers in Ctrl. Macros and gcode programs can now invoke the
tool changer with:
(MSG,HOOK:droptool:)
(MSG,HOOK:grabtool:)
(MSG,HOOK:release:)
(MSG,HOOK🗜️)
block_unpause + auto_resume mirrors the W-axis hooks: the program
pauses while the ESP runs the pneumatic sequence and resumes when
done. Soft timeouts match the worst-case ESP sequence durations.
The previous fix routed (MSG,HOOK:...) lines through state.messages
and then immediately ack'd them to suppress the user-visible popup.
But state changes are debounced 0.25s before listeners fire, so the
HOOK message was already ack'd (removed from the list) by the time
Hooks._on_state_change saw the update - and the hook never ran.
Add Hooks.dispatch_hook_message() as a direct entry point and call
it from Planner._add_message. HOOK lines are dispatched synchronously
from the planner thread; the user message list is left untouched, so
no popup leaks and no debounce race.
Three fixes for macro/W-axis interaction:
1. run_macro raced the file selection. The frontend mutated
state.selected client-side and immediately fired api.put('start').
Selection on the server is a side effect of GET /api/file/<name>
(FileHandler.get calls state.select_file). The GET request was
often still in flight when start ran, so mach.start() executed
whichever file was selected last - pressing W Down would re-run
W Up. Now run_macro awaits the file fetch before starting.
2. (MSG,HOOK:aux:N) lines, used as the IPC channel between the
W-axis preprocessor and the Hooks system, were leaking to the
user as message popups (because the planner forwards every
(MSG,...) comment to state.messages). Filter HOOK: messages in
Planner._add_message: still pushed through state.messages so
Hooks._on_state_change can dispatch them, but immediately
acked so the UI doesn't render them.
3. AuxPreprocessor only ran at upload time (FileHandler.put_ok and
Mach.mdi). Files written via scp, restored from a config backup,
or hand-edited still contained raw W tokens that the planner
couldn't parse. Run preprocess_file in Planner.load() too. It's
idempotent (no-op when no W tokens remain) so re-loading a
already-rewritten file is free.
Old defaults (4000 fast / 400 slow / 200 backoff / 16000 accel /
200 start) were never aggressive in practice because the user-
saved config drifted to even lower values (600/80/110). Re-tune
the DEFAULTS dict to values that are sensible at 25 steps/mm:
home_fast_sps 2500 ~100 mm/s seek
home_slow_sps 250 ~10 mm/s re-engage
home_backoff_steps 400 ~16 mm clear hysteresis
step_max_sps 4000 ~160 mm/s normal-move cap
step_accel_sps2 12000
These only affect machines without an existing aux.json. The Pi
at 10.1.10.55 was patched manually.
home() previously matched the wrong [home] line (firmware-side bug,
fixed in auxcnc) and even when it would have matched, it tried to
shift the step counter by writing 'WPOS <n>' after homing. The ESP's
WPOS handler clears HOMED, so a bbctrl restart would forget the home
state.
Push the desired step counter via HOMECFG zero= (firmware writes it
into the counter at the end of a successful HOME, leaving HOMED set).
home() now only reads the terminal [home] line; no post-home counter
fixup.
Measured on onefinity.local (Pi 3, Raspbian Stretch, bbctrl 1.6.7).
Before -> after:
bbctrl listen boot+20.6s -> boot+12.4s (-8.2s)
host -> /api/config/load 28.2s -> 22.5s (-5.7s)
The 4 changes (each independently revertable):
1. scripts/bbserial-rebind.service: do the bbserial unbind + reload
in a dedicated unit ordered Before=bbctrl.service, instead of in
rc.local AFTER bbctrl is already listening on the serial port.
Eliminates a full bbctrl restart mid-boot.
2. scripts/bbctrl.service: drop "After=network.target". bbctrl talks
to the AVR on a local serial port and to the LCD on I2C; it does
not need DHCP / network-online to come up. Also adds explicit
ordering after the new bbserial-rebind unit.
3. scripts/rc.local.fast: trimmed rc.local that no longer touches
bbserial and backgrounds 'startx' so chromium launches in
parallel with bbctrl rather than after rc.local finishes.
4. src/py/bbctrl/Planner.py: lazy-import camotics.gplan. Costs ~130ms
on cold cache, deferred from import-time to ctrl.mach init.
5. (bonus) src/py/bbctrl/Log.py: tolerate FileNotFoundError in
_rotate(). The improved boot path exposed a pre-existing log
rotator bug that crashed bbctrl on first start when bbctrl.log.16
was missing.
- Trace reads /proc/stat btime and /proc/uptime at import so every
event in /api/diag/timing can be expressed as 'seconds since
power-on' (uptime_at_anchor + ev.t).
- Web.StaticFileHandler.prepare emits 'web.first_root_get' the first
time chromium hits / or /index.html, so we can see when the kiosk
browser actually started loading the UI on cold boot.
Add a lightweight, self-contained phase tracer for measuring end-to-end
bbctrl restart and Pi boot time. Disabled by setting BBCTRL_TRACE=0.
- src/py/bbctrl/Trace.py: monotonic-anchored event log + sd_notify helper.
- bbctrl/__init__.py: marks for imports, args parsed, ioloop, web init,
listen, and an sd_notify READY=1 once HTTP is bound.
- bbctrl/Ctrl.py: spans around each subsystem (avr, i2c, lcd, mach,
preplanner, jog, pwr, hooks, aux, mach.connect).
- bbctrl/Comm.py: avr.firmware_rebooted mark.
- bbctrl/Web.py: TimingHandler (GET /api/diag/timing) and
UITimingHandler (PUT /api/diag/timing/ui), plus a ws.first_open mark.
- src/js/restart-timing.js + app.js: UI-side performance.now() marks
(script.load, ws.open, ws.first_msg, ui.first_state, window.load),
posted once to the controller.
- scripts/bbctrl.service: stdout/stderr -> journal so TRACE lines are
visible via journalctl -u bbctrl. (Was StandardOutput=null.)
Revert: git revert this commit. To disable at runtime without
reverting, set BBCTRL_TRACE=0 in the bbctrl service environment.
Rather than rebuild gplan + the AVR firmware to add a true 7th axis,
we treat W as a synchronous out-of-band axis that moves between G-code
blocks. The pipeline:
upload -> AuxPreprocessor rewrites W tokens into (MSG,HOOK:aux:N)
comments -> planner sees only XYZ + messages -> Hooks fires the
registered internal handler -> AuxAxis sends STEPS/HOME over serial
to the ESP and blocks the planner until done.
New files:
src/py/bbctrl/AuxAxis.py serial worker + RPC layer
src/py/bbctrl/AuxPreprocessor.py G-code rewriter
docs/AUX_W_AXIS.md design + ops notes
Changed:
Hooks.py register_internal(); fix the (MSG,HOOK:...) listener
to read the 'messages' state list (was broken before)
Ctrl.py instantiate AuxAxis, register aux/aux_rel/aux_home/
aux_setzero hooks
FileHandler.py rewrite uploads in place when they use W
Mach.py rewrite W tokens in MDI input the same way
Web.py REST endpoints under /api/aux/*
The ESP firmware in ../auxcnc was extended in lockstep: HOME, HOMECFG
(NVS-persisted), WPOS, HOMED?, LIMIT?, abortable STEPS with
limit-aware abort, trapezoidal ramps, deterministic [topic] reply
tokens, [boot] banner.
Real-time decisions (limit switch, step pulses) live on the ESP. The
host owns mm units, soft limits, and aux_homed bookkeeping. ESP
reboot mid-job clears aux_homed and surfaces a message; per design
manual jogs are still allowed without homing.
- Blocking hooks (block_unpause: true, default for tool-change) run
in a background thread and gate Mach.unpause() via can_unpause()
- Machine stays in HOLDING state while hook runs — AVR steppers idle,
spindle state preserved, position locked
- auto_resume option to unpause automatically after hook completes
- E-stop cancels any running hook immediately
- Hook status pushed to frontend via state (hook_busy, hook_event)
- GET /api/hooks/status endpoint for polling
- Non-blocking hooks (program-start, program-end, etc.) fire-and-forget
- New Hooks module (src/py/bbctrl/Hooks.py) that watches controller state
and fires webhooks or scripts on events:
- tool-change (M6), program-start, program-end, pause, estop,
homing-start, homing-end, custom (via MSG comments)
- API endpoints:
- GET /api/hooks - get current hook config
- PUT /api/hooks/save - save hook config
- PUT /api/hooks/fire/<event> - manually fire a hook (for testing)
- Hook config stored in hooks.json with two types:
- webhook: HTTP POST/PUT to external URL with JSON context
- script: run local command with env vars (HOOK_OLD_TOOL, etc.)
- Fix tornado.web.asynchronous deprecation in Camera.py
- Wired into Ctrl initialization and state listener system