Appendix: System Troubleshooting & Iteration
This appendix consolidates all engineering defects identified during the BoxBunny integration phase, covering the Arm Actuation and Padding subsystems. Each defect entry documents the symptom, root cause, and implemented resolution. All defects have been resolved (8) or mitigated (1).
Defect 1: Phantom 8–9A Idle Current
Layer: Firmware (CAN parsing)
Symptom: All motors reported ~8–9 A current draws at idle, fluctuating between large positive and negative values.
Root Cause: The Damiao motor protocol encodes torque as a 12-bit integer in the CAN response frame. The firmware incorrectly parsed this as a 16-bit float, consuming the adjacent temperature byte. Temperature fluctuations caused the parsed torque (and reported current) to oscillate wildly.
Resolution: Corrected the CAN unpacking logic to cleanly extract the 12-bit MIT Torque field. Confirmed stable 0.00 A idle readings.
Status: ✅ Resolved
Defect 2: Motor Jitter & Boomerang Effect
Layer: Middleware (ROS 2)
Symptom: The arm would reach the target, reverse to origin, then proceed again — producing a "boomerang" oscillation.
Root Cause (A — Ghost Node): A stale GUI instance published all-zero targets at 10 Hz, conflicting with the active GUI.
Root Cause (B — 50 Hz Reset): Publishing CAN commands at the ROS 2 callback rate (50 Hz) continuously reset the Damiao internal trajectory planner.
Resolution: (A) Pre-launch killall -9 python3.
(B) Sparse Edge-Trigger: CAN only on position change >0.01 rad or
every 100 ms keep-alive.
Status: ✅ Resolved
Defect 3: Damiao 50 Hz Trajectory Reset
Layer: Firmware (CAN timing)
Symptom: Motors exhibited choppy, non-smooth motion when commands were published at the full ROS callback rate.
Root Cause: Each CAN position command restarts the Damiao motor's internal trajectory planner. At 50 Hz, the planner never completed a smooth ramp before being reset.
Resolution: Sparse Edge-Trigger strategy (described above). The motor's internal planner now has time to execute smooth trajectories between commands.
Status: ✅ Resolved
Defect 4: Jump-Back & Failed Sensorless Homing
Layer: Application (GUI logic)
Symptom: After a sequence ended, the arm jumped to an arbitrary position instead of returning to start.
Root Cause: The GUI's apply_dynamic_endstops()
function was overwritten when using set_target() via
sequence executor (not the same function as set_target_arm()).
The endstop clamp was applied to stale slider values.
Resolution: Unified the target-setting pathway. Additionally, the automated sensorless homing sequence was removed after three failure modes (spurious current spikes, gear mesh slack non-repeatability, Motor 2 torque resonance) and replaced with a Manual Calibration Framework.
Status: ✅ Resolved
Defect 5: MDDS10 PWM/DIR Pin Transposition
Layer: Firmware + Documentation
Symptom: Motor ran at constant full speed; speed slider had no effect; STOP command was ignored.
Root Cause: The wiring document transposed the AN1 (speed) and DIG1 (direction) function labels. Pin 3 was wired to AN1 but mapped as direction output (constant 5V = 100% speed). Pin 2 was wired to DIG1 but mapped as PWM (direction-pin ignores PWM).
Resolution: Firmware pin swap — no physical rewiring. Documentation corrected.
Status: ✅ Resolved
Defect 6: Confirmed PSU OVP Trip
Layer: Electrical (Power)
Symptom: Releasing the EXTEND button caused the PSU to trip and all systems lost power.
Root Cause: Abrupt PWM cut from full speed → zero. Rotor back-EMF injected onto 24V bus, exceeding the PSU's ~28V OVP threshold.
Resolution: _ramp_down() — 6 decreasing
PWM steps over 300 ms. Hardware TVS clamp recommended for permanent
fix.
Status: ⚠️ Mitigated (hardware TVS clamp pending)
Defect 6 Detail: Regenerative Braking & Back-EMF Management
The DC height motor operates as a generator during the deceleration phase of height adjustment. When the motor decelerates rapidly (e.g., an abrupt STOP command at speed), the collapsing magnetic flux produces a back-EMF voltage spike that is injected onto the shared 24V bus.
Software Mitigation — PWM Ramp-Down
A _ramp_down() method was implemented in the GUI
control layer (V3). Instead of issuing a single STOP command,
the method transmits six progressively decreasing
position commands over a 300 ms window, limiting the
rate of rotor deceleration and thereby capping the back-EMF
voltage below the OVP threshold.
Back-EMF Physics
The induced voltage (Vemf) is proportional to the rate of change of magnetic flux:
Vemf = −N · dΦ / dt ≈ Ke · ω
Where Ke is the motor's back-EMF constant and ω is the angular velocity at the moment of deceleration. By controlling dω/dt through the ramp-down, the firmware limits Vemf to below the OVP threshold.
Residual Risk & Recommended Future Work
The software ramp-down addresses the common case but does not protect against edge cases such as a user physically stopping the height column mid-travel. A hardware-level protection — either a TVS clamp diode or an Active Shunt Regulator on the 24V bus — is recommended as a permanent solution.
Defect 7: I²C Bus Hang on Long-Wire IMU Routing
Layer: Firmware (Electrical → Software boundary) — affects RM-6 (Padding / Impact Detection)
| Symptom | MPU6050 holds SDA permanently low, freezing the entire I²C bus; IMU readings drop to -1 (0xFFFF) without power cycle recovery |
| Root Cause | Long (30–40 cm) unshielded jumper wires introduce parasitic capacitance (~50–100 pF per wire). At 400 kHz Fast Mode, the I²C "Repeated Start" condition causes the MPU6050's state machine to misinterpret the condition as a data bit, latching SDA low indefinitely |
| Resolution | Hard STOP protocol — endTransmission(true) after every register write, forcing a full STOP + START sequence. Adds ~20 µs latency per read but eliminates the bus-hang failure mode |
| Status | ✅ Resolved |
Root-Cause Analysis
The MPU6050 implements I²C with an internal state machine that tracks bus conditions. When the master issues a Repeated Start (SR) — pulling SDA low while SCL is high without an intervening STOP — the sensor must detect the transition within a narrow timing window (tHD;STA ≥ 0.6 µs per the I²C spec). On short PCB traces (< 5 cm), this timing is comfortably met.
However, the BoxBunny padding assembly routes 30–40 cm 4-conductor jumper wires from each IMU breakout to the Teensy 4.1. At this length, parasitic capacitance introduces RC rise-time delays on both SDA and SCL. At 400 kHz Fast Mode, these delays can cause the MPU6050's state machine to misinterpret the Repeated Start as a data bit, latching SDA low indefinitely.
The fix replaces all Repeated Start sequences with a
Hard STOP + full START sequence
(endTransmission(true)). The STOP condition
unambiguously resets the MPU6050's state machine regardless of
parasitic capacitance.
Defect 8: Nyquist Blind-Spot in Strike Detection
Layer: Application (GUI signal processing) — affects RM-6 (Padding / Impact Detection)
| Symptom | Visible acceleration peaks in PyQtGraph plot exceed threshold but system fails to register strike events |
| Root Cause | GUI refreshes at 20 Hz (50 ms), but punch impulses last ~30 ms. Naïve "check latest sample" approach samples only 1 of ~10 accumulated data points per frame, missing inter-frame strikes — a Nyquist blind-spot |
| Resolution | Scan-window peak detection: np.max(mag_arr[-n_scan:]) scans all accumulated samples since last GUI tick (n_scan ≈ 10 at 200 Hz firmware / 20 Hz GUI) |
| Status | ✅ Resolved |
Root-Cause Analysis
The IMU firmware publishes accelerometer data at 200 Hz (5 ms sample period). The GUI processes this data in its Qt event loop at 20 Hz (50 ms tick period). Between each GUI tick, approximately 10 IMU samples accumulate in the subscription buffer.
The original detection logic checked only the most recent sample at each GUI tick:
# BEFORE (broken): checks only 1 of ~10 samples
if mag_arr[-1] > threshold:
publish_strike_event()
A punch impulse lasts approximately 20–30 ms. If the peak occurs between two GUI ticks, the latest sample may already be below the threshold — the peak is visible in the real-time plot but invisible to the point-in-time threshold check.
The fix scans all accumulated samples since the last tick:
# AFTER (fixed): scans all samples in the window n_scan = max(1, int(firmware_hz / gui_hz)) # ≈ 10 peak = np.max(mag_arr[-n_scan:]) if peak > threshold: publish_strike_event(zone=np.argmax(...))
Defect 9: Micro-ROS Agent Disconnect Hang
Layer: Firmware (micro-ROS transport)
Symptom: Killing the micro_ros_agent
left the Teensy permanently hung in AGENT_CONNECTED state (WSL-specific).
Root Cause: WSL USB passthrough drivers fail to signal DTR/RTS teardown to the Teensy when the host port closes.
Resolution: 1 Hz active ping
(rmw_uros_ping_agent(10, 1)). After 3 failed pings (1.5 s),
the firmware triggers a hardware silicon reset
(SCB_AIRCR = 0x05FA0004), guaranteeing a pristine state
and immediate re-handshake.
Status: ✅ Resolved
Design Note: Tactical Walking — Exploiting the Differential Coupling
The bevel gear "walking" effect described in Mechanical Design is typically characterised as a mechanical challenge requiring software compensation. However, during motion planning development, this same coupling was identified as an intentional choreographic asset for specific strike patterns.
The Jab Windup — Intentional Rearing Motion
A realistic jab requires a preparatory "windup" phase where the arm lifts before descending into the strike. With the coaxial differential, this compound motion emerges naturally from the gear coupling by commanding Motor 1 and Motor 2 to rotate in opposition, producing a "rearing" motion that lifts the training stick vertically before the subsequent downward strike.
This reframing — from "compensating an error" to "exploiting a mechanical property" — illustrates the design philosophy of the Upper Mechanism: the differential coupling is a 4-quadrant actuation space where same-direction rotation produces pure roll, opposite-direction produces amplified pitch, and intermediate ratios blend both axes to create fluid, compound strike trajectories.
Defect Summary
| # | Defect | Layer | Req | Status |
|---|---|---|---|---|
| 1 | Phantom current | Firmware | RM-5 | ✅ Resolved |
| 2 | Motor jitter | Middleware | RM-5 | ✅ Resolved |
| 3 | Trajectory reset | Firmware | RM-5 | ✅ Resolved |
| 4 | Jump-back + homing | Application | RM-5 | ✅ Resolved |
| 5 | MDDS10 pin swap | Firmware | RM-3 | ✅ Resolved |
| 6 | PSU OVP trip | Electrical | RM-5 | ⚠️ Mitigated (HW fix pending) |
| 7 | I²C bus hang | Firmware | RM-6 | ✅ Resolved |
| 8 | Nyquist blind-spot | Application | RM-6 | ✅ Resolved |
| 9 | Micro-ROS hang | Firmware | RM-5 | ✅ Resolved |