feat: PID auto-tune (Issue #531) #541

Closed
sl-jetson wants to merge 0 commits from sl-firmware/issue-531-pid-autotune into main
Collaborator

Summary

  • Firmware: Relay feedback auto-tune state machine on FC; Ziegler-Nichols Kp/Ki/Kd computation; pid_flash_save()/pid_flash_load() persist gains to STM32F722 sector 7 flash
  • JLink protocol: Add JLINK_CMD_PID_SAVE (0x0A) command and JLINK_TLM_PID_RESULT (0x83) telemetry with confirmed save/fail response
  • ROS2 node: Complete ZN formula (adds Ki), JLink serial client sends PID_SET + PID_SAVE frames after relay oscillation converges

Test plan

  • Boot with no saved PID → defaults load (Kp=35, Ki=1, Kd=1)
  • ros2 service call /saltybot/autotune_pid std_srvs/srv/Trigger — relay oscillates, gains computed
  • Verify JLINK_TLM_PID_RESULT received with saved_ok=1
  • Power-cycle FC — confirm /imu pitch stabilises with saved gains
  • Safety: autotune service rejects request while armed; PID_SAVE ignored while BALANCE_ARMED

Closes #531

🤖 Generated with Claude Code

## Summary - **Firmware**: Relay feedback auto-tune state machine on FC; Ziegler-Nichols Kp/Ki/Kd computation; `pid_flash_save()`/`pid_flash_load()` persist gains to STM32F722 sector 7 flash - **JLink protocol**: Add `JLINK_CMD_PID_SAVE (0x0A)` command and `JLINK_TLM_PID_RESULT (0x83)` telemetry with confirmed save/fail response - **ROS2 node**: Complete ZN formula (adds Ki), JLink serial client sends `PID_SET` + `PID_SAVE` frames after relay oscillation converges ## Test plan - [ ] Boot with no saved PID → defaults load (Kp=35, Ki=1, Kd=1) - [ ] `ros2 service call /saltybot/autotune_pid std_srvs/srv/Trigger` — relay oscillates, gains computed - [ ] Verify `JLINK_TLM_PID_RESULT` received with `saved_ok=1` - [ ] Power-cycle FC — confirm `/imu` pitch stabilises with saved gains - [ ] Safety: autotune service rejects request while armed; PID_SAVE ignored while BALANCE_ARMED Closes #531 🤖 Generated with [Claude Code](https://claude.com/claude-code)
sl-jetson added 1 commit 2026-03-07 09:56:47 -05:00
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>
sl-jetson closed this pull request 2026-03-07 13:47:03 -05:00

Pull request closed

Sign in to join this conversation.
No Reviewers
No Label
1 Participants
Notifications
Due Date
No due date set.
Dependencies

No dependencies set.

Reference: seb/saltylab-firmware#541
No description provided.