Sensorless FOC on 1000KV drone motor with DRV8302 + Teensy 4.0 — Volt_Q unstable, integrator winding up

Hello for my college project i am trying to setup sensorless foc.

Board: Teensy 4.0 Driver: AliExpress DRV8302 (0.005Ω shunt, 12.22 V/V gain, low-side current sense) Motor: 1000KV BLDC drone motor, 7 pole pairs, ~55mΩ phase resistance, ~1mH inductance Library: SimpleFOC + SimpleFOCDrivers, MXLEMMING sensorless observer

I started by running the motor in open-loop voltage mode to characterize it, and then tried switching to foc_current torque control with the MXLEMMING observer.

Motor characterization results:

  • Phase resistance: 0.055 Ω (phase-phase 0.11Ω)

  • Phase inductance: 0.001 H (1mH Q-axis , 1.1mH D axis)

  • KV: 1000 rpm/V

  • Pole pairs: 7

  • Current sense ADC offsets (Teensy 3.3V ADC, 12-bit):

    • Offset A: ~1.670 V

    • Offset B: ~1.668 V

    • Offset C: ~1.659 V (These look correct — midpoint of 3.3V supply)

For the current sensing on DRV8302 i got help from (with a litle twick of adding external refference the teensy 3.3V to the DRV8302 current sense)

The Problem

With the code below, Iq slowly drifts toward the target (0) but never locks on, and Volt_Q swings wildly between ±1500V equivalent — clearly the integrator is winding up without any effective clamping.

Monitor output (_MON_CURR_Q | _MON_VOLT_Q):

0.0000    -0.0264
...
-0.9000   -2200.0
-1.0000    3500.0 
#include <SimpleFOC.h>
#include <SimpleFOCDrivers.h>
#include "encoders/MXLEMMING_observer/MXLEMMINGObserverSensor.h"

#define INH_A    6
#define INH_B    5
#define INH_C    4
#define EN_GATE  7
#define M_PWM   12
#define M_OC    11
#define OC_ADJ   9
#define GAIN    10
#define DC_CAL   8
#define PIN_NFAULT 15
#define IOUTA   17
#define IOUTB   18
#define IOUTC   19

BLDCMotor motor = BLDCMotor(7, 0.055f, 1000.0f, 0.001f);
BLDCDriver3PWM driver = BLDCDriver3PWM(INH_A, INH_B, INH_C, EN_GATE);
//shunt of drv8302 0.005 Ohms and the gain is 12.22 V/V
LowsideCurrentSense cs = LowsideCurrentSense(0.005f, 12.22f, IOUTA, IOUTB, IOUTC);
MXLEMMINGObserverSensor observer = MXLEMMINGObserverSensor(motor);

volatile bool flag_nfault = false;
void isr_nfault() { flag_nfault = true; }

Commander command = Commander(Serial);
void doTarget(char* cmd) { command.scalar(&motor.target, cmd); }
void doMotor(char* cmd)  { command.motor(&motor, cmd); }

void setup() {
  Serial.begin(460800);
  delay(300);
  SimpleFOCDebug::enable(&Serial);

  // DRV8302 config
  pinMode(M_OC,  OUTPUT); digitalWrite(M_OC,  LOW);
  pinMode(M_PWM, OUTPUT); digitalWrite(M_PWM, HIGH);
  pinMode(OC_ADJ,OUTPUT); digitalWrite(OC_ADJ,HIGH);
  pinMode(GAIN,  OUTPUT); digitalWrite(GAIN,  LOW);
  pinMode(DC_CAL,OUTPUT); digitalWrite(DC_CAL,LOW);
  pinMode(PIN_NFAULT, INPUT_PULLUP);
  attachInterrupt(digitalPinToInterrupt(PIN_NFAULT), isr_nfault, FALLING);

  driver.voltage_power_supply = 12.0f;
  driver.pwm_frequency = 20000;
  driver.init();
  motor.linkDriver(&driver);

  cs.linkDriver(&driver);
  cs.init();
  cs.gain_a *= -1; //inv gains in DRV8302
  cs.gain_b *= -1;
  cs.gain_c *= -1;
  cs.skip_align = true;
  motor.linkCurrentSense(&cs);

  motor.linkSensor(&observer);

  motor.torque_controller = TorqueControlType::foc_current;
  motor.controller        = MotionControlType::torque;
  motor.voltage_limit     = 2.0f;
  motor.current_limit     = 1.0f;

  motor.PID_current_q.P           = 0.05f;
  motor.PID_current_q.I           = 5.0f;
  motor.PID_current_q.limit       = 2.0f;
  motor.PID_current_q.output_ramp = 500.0f;
  motor.PID_current_d.P           = 0.05f;
  motor.PID_current_d.I           = 5.0f;
  motor.PID_current_d.limit       = 2.0f;
  motor.PID_current_d.output_ramp = 500.0f;
  motor.LPF_current_q.Tf = 0.01f;
  motor.LPF_current_d.Tf = 0.01f;

  motor.sensor_direction    = Direction::CW;
  motor.zero_electric_angle = 0.0f;

  motor.init();
  motor.initFOC();

  motor.useMonitoring(Serial);
  motor.monitor_downsample = 100;
  motor.monitor_variables  = _MON_CURR_Q | _MON_VOLT_Q;

  command.add('T', doTarget, "target Iq [A]");
  command.add('M', doMotor,  "motor config");
}

void loop() {
  motor.loopFOC();
  motor.move();
  command.run();
  motor.monitor();
  if (flag_nfault) { flag_nfault = false; Serial.println("DRV: nFAULT!"); }
}

I am not very familiar with pid tuning and the library. I would gladly appreciate your help .
Thank you !!!