- can_driver: add filter bank 15 (all ext IDs → FIFO1) and widen bank 14
to accept all standard IDs; add can_driver_send_ext/std and ext/std
frame callbacks (can_driver_set_ext_cb / can_driver_set_std_cb)
- vesc_can: VESC 29-bit extended CAN protocol driver — send RPM to IDs 56
and 68 (FSESC 6.7 Pro Mini Dual), parse STATUS/STATUS_4/STATUS_5
big-endian payloads, alive timeout, JLINK_TLM_VESC_STATE at 1 Hz
- orin_can: Orin↔FC standard CAN protocol — HEARTBEAT/DRIVE/MODE/ESTOP
commands in, FC_STATUS + FC_VESC broadcast at 10 Hz
- jlink: add JLINK_TLM_VESC_STATE (0x8E), jlink_tlm_vesc_state_t (22 bytes),
jlink_send_vesc_state_tlm()
- main: wire vesc_can_init/orin_can_init; replace can_driver_send_cmd with
vesc_can_send_rpm; inject Orin CAN speed/steer into balance PID; add
Orin CAN estop/clear handling; add orin_can_broadcast at 10 Hz
- test: 56-test host-side suite for vesc_can; test/stubs/stm32f7xx_hal.h
minimal HAL stub for all future host-side tests
Safety: balance PID runs independently on Mamba — if Orin CAN link drops
(orin_can_is_alive() == false) the robot continues balancing in-place.
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
Closed-loop yaw-rate controller that converts Jetson Twist.angular.z
to a differential wheel speed offset using IMU gyro Z as feedback.
- include/steering_pid.h + src/steering_pid.c: PID with anti-windup
(integral clamped to ±200 counts) and rate limiter (10 counts/ms
max output change) to protect balance PID from sudden steering steps.
JLINK_TLM_STEERING (0x8A) telemetry at 10 Hz.
- include/mpu6000.h + src/mpu6000.c: expose yaw_rate (board_gz) in
IMUData so callers have direct bias-corrected gyro Z feedback.
- include/jlink.h + src/jlink.c: add JLINK_TLM_STEERING (0x8A),
jlink_tlm_steering_t (8 bytes), jlink_send_steering_tlm().
- test/test_steering_pid.c: 78 unit tests (host build with gcc),
all passing.
Usage (main loop):
steering_pid_set_target(&s, jlink_state.steer * STEER_OMEGA_SCALE);
int16_t steer_out = steering_pid_update(&s, imu.yaw_rate, dt);
motor_driver_update(&motor, balance_cmd, steer_out, now_ms);
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
Adds a slow-adapting terrain slope estimator (IIR tau=5s) that decouples
the robot's balance offset from genuine ground incline. The balance
controller subtracts the slope estimate from measured pitch so the PID
balances around the slope surface rather than absolute vertical.
- include/slope_estimator.h + src/slope_estimator.c: first-order IIR
filter clamped to ±15°; JLINK_TLM_SLOPE (0x88) telemetry at 1 Hz
- include/jlink.h + src/jlink.c: add JLINK_TLM_SLOPE (0x88),
jlink_tlm_slope_t (4 bytes), jlink_send_slope_tlm()
- include/balance.h + src/balance.c: integrate slope_estimator into
balance_t; update, reset on tilt-fault and disarm
- test/test_slope_estimator.c: 35 unit tests, all passing
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
Keep both Issue #531 (PID_RESULT telemetry) and Issue #533 (BATTERY
telemetry) additions in include/jlink.h and src/jlink.c.
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
Implement Ziegler-Nichols relay feedback auto-tuning with flash persistence:
Firmware (STM32F722):
- pid_flash.c/h: erase+write Kp/Ki/Kd to flash sector 7 (0x0807FFC0),
magic-validated; load on boot to restore saved tune
- jlink.h: add JLINK_CMD_PID_SAVE (0x0A) and JLINK_TLM_PID_RESULT (0x83)
with jlink_tlm_pid_result_t struct and pid_save_req flag in JLinkState
- jlink.c: dispatch JLINK_CMD_PID_SAVE -> pid_save_req; add
jlink_send_pid_result() to confirm flash write outcome over USART1
- main.c: load saved PID from flash after balance_init(); handle
pid_save_req in main loop (disarmed-only, erase stalls CPU ~1s)
Jetson ROS2 (saltybot_pid_autotune):
- pid_autotune_node.py: add Ki to Ziegler-Nichols formula (ZN PID:
Kp=0.6Ku, Ki=1.2Ku/Tu, Kd=0.075KuTu); add JLink serial client that
sends JLINK_CMD_PID_SET + JLINK_CMD_PID_SAVE after tuning completes
- autotune_config.yaml: add jlink_serial_port and jlink_baud_rate params
Trigger: ros2 service call /saltybot/autotune_pid std_srvs/srv/Trigger
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
USART1 IDLE interrupt (DMA circular RX) was calling HAL_UART_IRQHandler
mid-frame during polling HAL_UART_Transmit, resetting gState and causing
leading nulls / truncated frames on the Jetson telemetry link at 921600 baud.
Fix: introduce jlink_tx_locked() which disables USART1_IRQn around every
blocking HAL_UART_Transmit call, preventing IRQHandler from corrupting
gState while the TX loop is running. A s_tx_busy flag drops any
re-entrant caller (ESC debug, future USART6/VESC paths).
Both jlink_send_telemetry (50 Hz) and jlink_send_power_telemetry (1 Hz)
now use jlink_tx_locked(). Also correct the stale config.h comment that
misidentified the Jetson link as USART6 (it moved to USART1 in Issue #120).
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
Adds STM32F7 STOP-mode power management with <10ms wake latency:
- power_mgmt.c: state machine (ACTIVE→SLEEP_PENDING→SLEEPING→WAKING),
30s idle timeout (PM_IDLE_TIMEOUT_MS), 3s LED fade before STOP,
gate SPI3/I2S3+SPI2+USART6+UART5 on sleep (clock-only, state preserved),
EXTI1(PA1/CRSF)+EXTI7(PB7/JLink)+EXTI4(PC4/IMU) wake sources,
PLL restore after STOP (PLLM=8/N=216/P=2 → 216MHz), uwTick save/restore
- Peripheral gating: I2S3, SPI2(OSD), USART6, UART5 disabled during STOP;
SPI1(IMU), UART4(CRSF), USART1(JLink), I2C1 remain active as wake sources
- Sleep LED: triangle-wave pulse (2s period) on LED1 during SLEEP_PENDING,
software PWM in main loop (1-bit, pm_pwm_phase vs brightness)
- IWDG: fed just before WFI; <10ms wake << 50ms WATCHDOG_TIMEOUT_MS
- JLink: JLINK_CMD_SLEEP=0x09, JLINK_TLM_POWER=0x81 (11-byte power frame
at 1Hz: power_state, est_total_ma, est_audio_ma, est_osd_ma, idle_ms)
- main.c: power_mgmt_init(), activity() on CRSF/JLink/armed, tick() when
disarmed, sleep_req handler, LED PWM, JLINK_TLM_POWER telemetry
- config.h: PM_* constants, PM_CURRENT_*_MA estimates, PM_TLM_HZ
- test_power_mgmt.py: 72 tests passing (state machine, LED, gating,
current estimates, JLink protocol, wake latency, hardware constants)
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>