sl-controls 6dfb5640db feat(imu): MPU6000 sensor fusion with complementary filter
Add src/mpu6000.c implementing a complementary filter (α=0.98) on top of
the existing icm42688 SPI driver. Fixes wrong scale factors in balance.c
(was ±250°/s / ±2g; hardware is configured ±2000°/s / ±16g). Fusion now
lives in the IMU driver layer; balance_update() consumes IMUData directly.

- mpu6000_init(): calls icm42688_init(), seeds filter state
- mpu6000_read(): reads raw SPI, applies complementary filter, returns
  fused pitch (degrees) + pitch_rate (°/s) + accel_x/z (g)
- balance.c: removes duplicated fusion code, uses IMUData.pitch
- main.c: switches to mpu6000_init()/mpu6000_read(), updates telemetry

Co-Authored-By: Claude Sonnet 4.6 <noreply@anthropic.com>
2026-02-28 12:26:28 -05:00

89 lines
2.3 KiB
C

#include "balance.h"
#include "config.h"
#include <math.h>
void balance_init(balance_t *b) {
b->state = BALANCE_DISARMED;
b->pitch_deg = 0.0f;
b->pitch_rate = 0.0f;
b->integral = 0.0f;
b->prev_error = 0.0f;
b->motor_cmd = 0;
/* Default PID — conservative starting point */
b->kp = PID_KP;
b->ki = PID_KI;
b->kd = PID_KD;
b->setpoint = 0.0f;
/* Safety defaults from config */
b->max_tilt = MAX_TILT_DEG;
b->max_speed = MAX_SPEED_LIMIT;
}
void balance_update(balance_t *b, const IMUData *imu, float dt) {
if (dt <= 0.0f || dt > 0.1f) return; /* Sanity check dt */
/* Consume fused angle from mpu6000 complementary filter */
b->pitch_deg = imu->pitch;
b->pitch_rate = imu->pitch_rate;
/* Safety: tilt cutoff */
if (b->state == BALANCE_ARMED) {
if (fabsf(b->pitch_deg) > b->max_tilt) {
b->state = BALANCE_TILT_FAULT;
b->motor_cmd = 0;
b->integral = 0.0f;
return;
}
}
if (b->state != BALANCE_ARMED) {
b->motor_cmd = 0;
b->integral = 0.0f;
b->prev_error = 0.0f;
return;
}
/* PID */
float error = b->setpoint - b->pitch_deg;
/* Proportional */
float p_term = b->kp * error;
/* Integral with anti-windup */
b->integral += error * dt;
if (b->integral > PID_INTEGRAL_MAX) b->integral = PID_INTEGRAL_MAX;
if (b->integral < -PID_INTEGRAL_MAX) b->integral = -PID_INTEGRAL_MAX;
float i_term = b->ki * b->integral;
/* Derivative on measurement (avoids setpoint kick) */
float d_term = b->kd * (-b->pitch_rate);
/* Sum and clamp */
float output = p_term + i_term + d_term;
if (output > (float)b->max_speed) output = (float)b->max_speed;
if (output < -(float)b->max_speed) output = -(float)b->max_speed;
b->motor_cmd = (int16_t)output;
b->prev_error = error;
}
void balance_arm(balance_t *b) {
if (b->state == BALANCE_DISARMED) {
/* Only arm if roughly upright */
if (fabsf(b->pitch_deg) < 10.0f) {
b->integral = 0.0f;
b->prev_error = 0.0f;
b->motor_cmd = 0;
b->state = BALANCE_ARMED;
}
}
}
void balance_disarm(balance_t *b) {
b->state = BALANCE_DISARMED;
b->motor_cmd = 0;
b->integral = 0.0f;
}