Issue #680 — IMU mount angle calibration:
- imu_cal_flash.h/.c: store pitch/roll offsets in flash sector 7
(0x0807FF00, 64 bytes; preserves PID records across sector erase)
- mpu6000_set_mount_offset(): subtracts offsets from pitch/roll output
- mpu6000_has_mount_offset(): reports cal_status=2 to Orin
- 'O' CDC command: capture current pitch/roll → save to flash → ACK JSON
- Load offsets on boot; report in printf log
CAN telemetry correction (Tee: production has no USB to Orin):
- FC_IMU (0x402): pitch/roll/yaw/cal_status/balance_state at 50 Hz
- orin_can_broadcast_imu() rate-limited to ORIN_IMU_TLM_HZ (50 Hz)
- FC_BARO (0x403): pressure_pa/temp_x10/alt_cm at 1 Hz (Issue #672)
- orin_can_broadcast_baro() rate-limited to ORIN_BARO_TLM_HZ (1 Hz)
Issue #685 — LED CAN override:
- ORIN_CAN_ID_LED_CMD (0x304): pattern/brightness/duration_ms from Orin
- orin_can_led_override volatile state + orin_can_led_updated flag
- main.c: apply pattern to LED state machine on each LED_CMD received
Orin side:
- saltybot_can_node.py: production SocketCAN bridge — reads 0x400-0x403,
publishes /saltybot/imu, /saltybot/balance_state, /saltybot/barometer;
subscribes /cmd_vel → 0x301 DRIVE; /saltybot/leds → 0x304 LED_CMD;
sends 0x300 HEARTBEAT at 5 Hz; sends 0x303 ESTOP on shutdown
- setup.py: register saltybot_can_node entry point + uart_bridge launch
Fix: re-apply --defsym __stack_end=_estack-0x1000 linker fix to branch
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>
On boot, before the main loop, sample 1000 gyro readings (~1s) while
board is held still. Compute per-axis mean offset (sensor-frame raw LSBs)
and subtract from all subsequent readings in mpu6000_read().
- mpu6000_calibrate(): LED1+LED2 solid ON during 1s sample window,
resets filter state to zero once bias is known
- mpu6000_is_calibrated(): gate; main loop blocks arming and USB
streaming until calibration completes
- Bias subtracted in sensor frame before CW270 axis transform + scale,
so all three axes (pitch/roll/yaw rate) benefit
- config.h: GYRO_CAL_SAMPLES=1000
- No flash storage — recalibrate fresh each boot (bias varies with temp)
Closes#21 (3.5°/s yaw drift), #23 (gyro bias calibration on boot).
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
Issue #12 — Roll displayed as pitch:
- Firmware was sending r=pitch_rate (wrong). Changed to r=roll_deg*10.
- mpu6000.c: add roll complementary filter (accel atan2(ay,az) +
gyro gy integration, same COMP_ALPHA=0.98 as pitch).
- IMUData: add roll and yaw fields.
- UI: updateIMU() now uses data.r/10 for roll (not client-side filter
that computed from ax/ay/az which firmware never sent).
- Three.js: roll -> rotation.z (banking), pitch -> rotation.x (tipping)
— axes were already correct, fix was the firmware data.
Issue #13 — Add yaw telemetry:
- Firmware: gyro Z integration (gz * dt) → s_yaw, sent as y=yaw_deg*10.
Gyro-only, drifts — no magnetometer.
- IMUData: yaw field added.
- UI: yaw -> rotation.y (spinning on vertical axis). Displayed in HUD.
- UI: YAW RESET button captures current yaw as new zero reference
(client-side offset, no new firmware command needed).
Closes#12, #13.
Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>