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>
44 lines
1.4 KiB
C
44 lines
1.4 KiB
C
#ifndef MPU6000_H
|
|
#define MPU6000_H
|
|
|
|
#include <stdint.h>
|
|
#include <stdbool.h>
|
|
|
|
typedef struct {
|
|
float pitch; // degrees, filtered (complementary filter)
|
|
float pitch_rate; // degrees/sec (raw gyro pitch axis)
|
|
float roll; // degrees, filtered (complementary filter)
|
|
float yaw; // degrees, gyro-integrated (drifts — no magnetometer)
|
|
float yaw_rate; // degrees/sec (raw gyro Z / board_gz, Issue #616)
|
|
float accel_x; // g
|
|
float accel_z; // g
|
|
} IMUData;
|
|
|
|
bool mpu6000_init(void);
|
|
|
|
/*
|
|
* Sample gyro for ~1s to compute per-axis bias offsets.
|
|
* Must be called after mpu6000_init() with the board held still.
|
|
* Blocks ~1s. LED1+LED2 solid during calibration.
|
|
* IWDG must NOT be running when this is called (call before safety_init()).
|
|
*/
|
|
void mpu6000_calibrate(void);
|
|
|
|
/* Returns true once mpu6000_calibrate() has completed. */
|
|
bool mpu6000_is_calibrated(void);
|
|
|
|
void mpu6000_read(IMUData *data);
|
|
|
|
/*
|
|
* mpu6000_set_mount_offset(pitch_deg, roll_deg) — set mount angle offsets.
|
|
* These are subtracted from the pitch and roll outputs in mpu6000_read().
|
|
* Load via imu_cal_flash_load() on boot; update after 'O' CDC command.
|
|
* Issue #680.
|
|
*/
|
|
void mpu6000_set_mount_offset(float pitch_deg, float roll_deg);
|
|
|
|
/* Returns true if non-zero mount offsets have been applied (Issue #680). */
|
|
bool mpu6000_has_mount_offset(void);
|
|
|
|
#endif
|