#ifndef MPU6000_H #define MPU6000_H #include #include 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