Tuning for hub motor?

Hi, I’ve just done a round of tuning for a 15PP scooter humb motor and getting reasonalbe results I think , but wanted to compare notes with someone else.

Controller: NUCLEO64-G431
DRIVER: DRV8302 board
Motor: 15PP hub scooter motor
Sensor: HALL
ALGO: SImpleFOC-Current mode

Tuning dump

// control loop type and torque mode
motor.torque_controller = TorqueControlType::foc_current;
motor.controller = MotionControlType::angle;
motor.motion_downsample = 0.0;

// velocity loop PID
motor.PID_velocity.P = 0.7;
motor.PID_velocity.I = 0.7;
motor.PID_velocity.D = 0.0;
motor.PID_velocity.output_ramp = 200.0;
motor.PID_velocity.limit = 1000.0;
// Low pass filtering time constant
motor.LPF_velocity.Tf = 0.1;
// angle loop PID
motor.P_angle.P = 7.0;
motor.P_angle.I = 0.0;
motor.P_angle.D = 0.0;
motor.P_angle.output_ramp = 50.0;
motor.P_angle.limit = 27.0;
// Low pass filtering time constant
motor.LPF_angle.Tf = 0.0;
// current q loop PID
motor.PID_current_q.P = 1.0;
motor.PID_current_q.I = 40.0;
motor.PID_current_q.D = 0.0;
motor.PID_current_q.output_ramp = 0.0;
motor.PID_current_q.limit = 9.0;
// Low pass filtering time constant
motor.LPF_current_q.Tf = 0.02;
// current d loop PID
motor.PID_current_d.P = 1.0;
motor.PID_current_d.I = 40.0;
motor.PID_current_d.D = 0.0;
motor.PID_current_d.output_ramp = 0.0;
motor.PID_current_d.limit = 9.0;
// Low pass filtering time constant
motor.LPF_current_d.Tf = 0.02;
// Limits
motor.velocity_limit = 27.0;
motor.voltage_limit = 9.0;
motor.current_limit = 1000.0;
// sensor zero offset - home position
motor.sensor_offset = 1859.404;
// general settings
// motor phase resistance
motor.phase_resistance = 0.0;
// pwm modulation settings
motor.foc_modulation = FOCModulationType::SinePWM;
motor.modulation_centered = 1.0;

Setup:

Code:

#include <Arduino.h>
#include <SimpleFOC.h>
#include “DRV8301.h”
#include “STM32HWEncoder.h”
#include <SimpleFOC.h>

#define CONTROL_TYPE (MotionControlType::angle)
#define SUPPLY_V (18)
#define DRIVER_V_LIMIT (18)
#define MOTOR_V_LIMIT (9)
#define SENSOR_ALIGN_V (2) //1

#define COMMANDER
#define CURSENS
#define CLOSED_LOOP
#define MONITOR
#define HALL
//#define USE_DRV8301
#define USE_DRV8302
//#define USE_SMOOTHSENSOR

#ifdef USE_SMOOTHSENSOR
#include “smoothsensor.h”
#endif

#define HB_IO (8)
#ifdef CLOSED_LOOP

HallSensor sensor = HallSensor(12, 14, 15, 15);

#endif // CLOSED_LOOP

#ifdef USE_DRV8302
DRV8302 gate_driver = DRV8302(2, 3, 4, 5, 6, 7); // nFAULT, M_PWM, M_OC, GAIN, OC_ADJ, EN_GATE
#endif // USE_DRV8302

// motor & driver instance
BLDCMotor motor = BLDCMotor(15); // hub
//BLDCMotor motor = BLDCMotor(15, 0.4, 28, 0.0004); // hub (for voltage mode)
BLDCDriver3PWM driver = BLDCDriver3PWM(PC0, PC1, PC2); // DRV8301/2

#ifdef CURSENS
// inline current sensor instance
//InlineCurrentSense current_sense = InlineCurrentSense(0.01f, 50.0f, A0, A2, _NC);
//LowsideCurrentSense current_sense = LowsideCurrentSense(0.005, 12.2, A0, A1, A2);
LowsideCurrentSense current_sense = LowsideCurrentSense(0.005, 12.2, A0, A1, _NC);
#endif

#ifdef HALL
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}
#endif // HALL

#ifdef COMMANDER
// commander communication instance
Commander command = Commander(Serial);
// void doMotor(char* cmd) { command.motor(&motor, cmd); }
void doTarget(char* cmd) {command.scalar(&motor.target, cmd);}
void doLimit(char* cmd) {command.scalar(&motor.voltage_limit, cmd);}
void doMotor(char* cmd) { command.motor(&motor, cmd); }
void doInduct(char* cmd) { command.scalar(&motor.phase_inductance, cmd); }
#endif

#ifdef USE_SMOOTHSENSOR
SmoothingSensor smooth = SmoothingSensor(sensor, motor);
#endif

char msgbuf[256];

void setup() {
Serial.begin(921600); // WARNING: low value like 115200 cause distorted FOC
// for timer analysis
//SimpleFOCDebug::enable(&Serial);
//delay(5000);
Serial.printf(“enter setup…\n”);

#ifdef CLOSED_LOOP
#ifdef HALL
sensor.pullup = Pullup::USE_INTERN;
sensor.enableInterrupts(doA, doB, doC);
#endif // HALL

sensor.init();

// link the motor to the sensor

#ifdef USE_SMOOTHSENSOR
#ifdef HALL
smooth.phase_correction = -_PI_6; // FOR HALL SENSOR
#endif
motor.linkSensor(&smooth);
#else
motor.linkSensor(&sensor);
#endif

#endif // CLOSED_LOOP

// driver config
// power supply voltage [V]
driver.voltage_power_supply = SUPPLY_V;
driver.voltage_limit = DRIVER_V_LIMIT;
driver.init();
#ifdef USE_DRV8301
// configure the DRV8301
gate_driver.begin(PWM_INPUT_MODE_3PWM, 0, SHUNT_GAIN_10);
_delay(100);
int reg1, reg2, reg3, reg4, fault;
gate_driver.get_regs(&reg1, &reg2, &reg3, &reg4);
fault = gate_driver.is_fault();
sprintf(msgbuf, “DRV8301: fault=%x, STATREG1=0x%.4x, STATREG2=0x%.4x, CTRLREG1=0x%.4x, CTRLREG2=0x%.4x”, fault, reg1, reg2, reg3, reg4);
Serial.println(msgbuf);
#endif // USES_DRV8301
#ifdef USE_DRV8302
gate_driver.begin(PWM_INPUT_MODE_3PWM, SHUNT_GAIN_10);
_delay(100);
#endif // USE_DRV8302

// link driver
motor.linkDriver(&driver);
// link current sense and the driver
#ifdef CURSENS
current_sense.linkDriver(&driver);
// current sense init and linking
if (current_sense.init())
Serial.println(“Current sense init success!”);
else{
Serial.println(“Current sense init failed!”);
return;
}
motor.linkCurrentSense(&current_sense);

#endif // CURSENS

#ifdef CLOSED_LOOP
// velocity loop PID
motor.PID_velocity.P = 0.7;
motor.PID_velocity.I = 0.7;
motor.PID_velocity.D = 0.0;
motor.PID_velocity.output_ramp = 200.0;
motor.PID_velocity.limit = 1000.0;
// Low pass filtering time constant
motor.LPF_velocity.Tf = 0.1;
// angle loop PID
motor.P_angle.P = 7.0;
motor.P_angle.I = 0.0;
motor.P_angle.D = 0.0;
motor.P_angle.output_ramp = 50.0;
motor.P_angle.limit = 27.0;
// Low pass filtering time constant
motor.LPF_angle.Tf = 0.0;

#ifdef CURSENS
motor.torque_controller = TorqueControlType::foc_current;

// current q loop PID
motor.PID_current_q.P = 1.0;
motor.PID_current_q.I = 40.0;
motor.PID_current_q.D = 0.0;
motor.PID_current_q.output_ramp = 0.0;
motor.PID_current_q.limit = 9.0;
// Low pass filtering time constant
motor.LPF_current_q.Tf = 0.02;
// current d loop PID
motor.PID_current_d.P = 1.0;
motor.PID_current_d.I = 40.0;
motor.PID_current_d.D = 0.0;
motor.PID_current_d.output_ramp = 0.0;
motor.PID_current_d.limit = 9.0;
// Low pass filtering time constant
motor.LPF_current_d.Tf = 0.02;
#endif // CURSENS

#endif // CLOSED_LOOP

// limts
motor.voltage_sensor_align = SENSOR_ALIGN_V;
//motor.controller = MotionControlType::torque;
motor.controller = CONTROL_TYPE;
// default voltage_power_supply
motor.velocity_limit = 27 ;
motor.voltage_limit = MOTOR_V_LIMIT;
motor.current_limit = 1000.0;

// set the inital target value
motor.target = 0;
// Serial.begin(115200); // WARNING: low value like 115200 cause distorted FOC
// comment out if not needed
#ifdef MONITOR
motor.useMonitoring(Serial);
motor.monitor_downsample = 0; // disable intially
motor.monitor_variables = _MON_TARGET | _MON_VOLT_Q | _MON_VOLT_D | _MON_CURR_Q | _MON_CURR_D | _MON_VEL | _MON_ANGLE; // monitor target velocity and angle
#endif

//motor.foc_modulation = SpaceVectorPWM;
// initialise motor
motor.init();
#ifdef CLOSED_LOOP
// align encoder and start FOC
motor.initFOC();
#endif

#ifdef COMMANDER
// subscribe motor to the commander
command.add(‘T’, doTarget, “target”); // ssss space
command.add(‘L’, doLimit, “voltage limit”);
command.add(‘I’, doInduct, “phase_inductance”);
command.add(‘M’,doMotor,“motor”);
#endif

Serial.printf(“setup complete…\n”);
_delay(1000);

pinMode(HB_IO, OUTPUT);
}

void loop() {

digitalWrite(HB_IO, 1);
#ifdef CLOSED_LOOP
// iterative setting FOC phase voltage
motor.loopFOC();
#endif // CLOSED_LOOP

// iterative function setting the outter loop target
motor.move();

#ifdef MONITOR
// motor monitoring
motor.monitor();
#endif // MONITOR

#ifdef COMMANDER
// user communication
command.run();
#endif // COMMANDER
digitalWrite(HB_IO, 0);

#if defined(USE_DRV8301) || defined(USE_DRV8302)
if (gate_driver.is_fault())
{
sprintf(msgbuf, “gate driver faulted”);
}

#endif // USE_DRV8302

}