Hmm, I still don’t see anything. Try printing the current a,b,c and motor.Ua,Ub,Uc voltages at the same time, to make sure it’s actually trying. And try printing while turning slowly in open loop mode to see what the current to voltage ratio should be (of course set motor.voltage_limit much lower before switching to open loop, since it applies full voltage at all times).
Here’s my code, for comparison. I always use sprintf for realtime output since Serial.print will block execution on STM32 if you call it twice within 20ms or so. However it does not support %f floating point numbers, so you have to multiply by 1000 and cast to int so the printed values are in millivolts and milliamps.
// RCTimer 5010 620kv lathe mini-spindle
#include <SimpleFOC.h>
#include <SimpleFOCDrivers.h>
#include <encoders/MXLEMMING_observer/MXLEMMINGObserverSensor.h>
typedef int8_t s8;
typedef uint8_t u8;
typedef int16_t s16;
typedef uint16_t u16;
typedef int32_t s32;
typedef uint32_t u32;
typedef int64_t s64;
typedef uint64_t u64;
#define SERVO_PULSE_PIN PA15
// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(7, 0.07f, 620, 0.000045f);
BLDCDriver6PWM driver = BLDCDriver6PWM(A_PHASE_UH, A_PHASE_UL, A_PHASE_VH, A_PHASE_VL, A_PHASE_WH, A_PHASE_WL);
LowsideCurrentSense currentSense = LowsideCurrentSense(0.003f, -64.0f/7.0f, A_OP1_OUT, A_OP2_OUT, A_OP3_OUT);
MXLEMMINGObserverSensor lemming = MXLEMMINGObserverSensor(motor);
extern volatile u16 adcBuffer1[];
float GetTemperature() { return adcBuffer1[3] * (345.2f / 4096.0f) - 56.2f; }
float GetBusVoltage() { return adcBuffer1[4] * ((169.0f+18.0f) / 18.0f * 3.3f / 4096.0f); }
float target = 0;
char printVariable = 0;
u16 servoPulse = 0xffff; // Servo tester 982-2039
LowPassFilter servoLPF(0.1f);
void ServoPulseUpdate() {
static u32 startTime = 0, lastPulseTime = 0;
static int pinState = 0;
u32 curTime = micros();
int newState = digitalRead(SERVO_PULSE_PIN);
if (newState != pinState) {
if ((pinState = newState)) // Update static variable and check if transitioned from low to high
startTime = curTime; // Transitioned from low to high: Start counting pulse time
else if (curTime > startTime + 850 && curTime < startTime + 2150) // Transitioned from high to low: Check if valid signal
servoPulse = (u16)(curTime - startTime), lastPulseTime = curTime;
else
servoPulse = 0xffff; // Pulse outside valid range
}
// Disable motor if no signal for over 100ms
if (curTime - lastPulseTime > 100000)
servoPulse = 0xffff;
}
void setup() {
// use monitoring with serial
Serial.setTx(PB3);
Serial.setRx(PB4);
Serial.begin(115200);
Serial.println(F_CPU);
pinMode(SERVO_PULSE_PIN, INPUT);
// For safety, make sure speed knob is turned to zero at startup.
while(servoPulse == 0xffff) { delayMicroseconds(50); ServoPulseUpdate(); }
while((servoPulse - 1000) * (6.5f / 1000.0f) > 10) { delayMicroseconds(50); ServoPulseUpdate(); }
// link the motor to the sensor
motor.linkSensor(&lemming);
// driver config
// power supply voltage [V]
driver.voltage_power_supply = 12; // Will be updated to measured voltage after current sense starts the ADC
driver.pwm_frequency = 25000;
driver.init();
// link the motor and the driver
motor.linkDriver(&driver);
// link current sense and the driver
currentSense.linkDriver(&driver);
// current sensing
currentSense.init();
if (GetBusVoltage() > 10 && GetBusVoltage() < 30) // Sanity check, e.g. powered by STLink with no battery connected
driver.voltage_power_supply = GetBusVoltage();
// no need for aligning
currentSense.skip_align = true;
motor.linkCurrentSense(¤tSense);
// aligning voltage [V]
motor.voltage_sensor_align = .6;
// index search velocity [rad/s]
motor.velocity_index_search = 3;
// set motion control loop to be used
motor.torque_controller = TorqueControlType::foc_current;
motor.controller = MotionControlType::torque;
motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
// contoller configuration
// default parameters in defaults.h
// velocity PI controller parameters
motor.PID_velocity.P = 0.1;
motor.PID_velocity.I = 10.0f;
motor.PID_velocity.D = 0.0f;
// default voltage_power_supply
motor.voltage_limit = 0;
motor.current_limit = 5;
// jerk control using voltage voltage ramp
// default value is 300 volts per sec ~ 0.3V per millisecond
motor.PID_velocity.output_ramp = 20;
// velocity low pass filtering time constant
motor.LPF_velocity.Tf = 0.01f;
// angle P controller
motor.P_angle.P = 20;
// maximal velocity of the position control
motor.velocity_limit = 5000 / 60 * _2PI;
// initialize motor
motor.init();
// align encoder and start FOC
motor.zero_electric_angle = 0; motor.sensor_direction = Direction::CW; // Lemming
motor.initFOC();
}
void loop() {
u32 loopTime = _micros();
ServoPulseUpdate();
static int voltageTarget = 0;
if (servoPulse == 0xffff)
voltageTarget = 0;
else {
target = -motor.current_limit; // Apply full torque, with max RPM controlled by voltage limit
int newTarget = servoLPF((servoPulse - 1000) * (650.0f / 1000.0f));
static const int speed[7] = { 10, 100, 200, 300, 400, 500, 600 };
int v;
for (v = sizeof(speed)/sizeof(speed[0])-1; v >= 0; v--)
if (newTarget >= speed[v])
break;
if (v < voltageTarget - 1) v += 1, voltageTarget = v < 0 ? 0 : v;
else if (v > voltageTarget) voltageTarget = v;
}
// limit the acceleration by ramping the output
float dt = 0.000050f, dv = voltageTarget - motor.voltage_limit, ramp = 20*dt; // Ramp at 20V/s
if(dv > ramp) motor.voltage_limit += ramp;
else if(dv < -ramp) motor.voltage_limit -= ramp;
else motor.voltage_limit = voltageTarget;
if (motor.voltage_limit == 0 && motor.enabled)
motor.disable(); // Disable passive braking effect
else if (motor.voltage_limit != 0 && !motor.enabled)
motor.enable();
motor.PID_current_q.limit = motor.PID_current_d.limit = motor.voltage_limit;
target = motor.voltage_limit == 0 ? 0 : -motor.current_limit;
motor.loopFOC();
motor.move(target);
loopTime = _micros() - loopTime;
static uint32_t lastPrintTime = 0;
u32 t = millis();
if (printVariable && t >= lastPrintTime + 50)
{
lastPrintTime = t;
PhaseCurrent_s c = currentSense.getPhaseCurrents();
DQCurrent_s f = currentSense.getFOCCurrents(motor.electrical_angle);
float dc = currentSense.getDCCurrent();
char string[256];
switch(printVariable)
{
case 'b': sprintf(string, "%i\n", (int)(GetBusVoltage()*1000)); break;
case 'h': sprintf(string, "%i\n", (int)(GetTemperature()*1000)); break;
case 'v': sprintf(string, "%i\n", (int)(motor.shaft_velocity*1000)); break;
case 'd': sprintf(string, "%+5i\n", (int)(dc*1000)); break;
case 'l': sprintf(string, "%i\n", loopTime); break;
case 'u': sprintf(string, "%+5i,%+5i,%+5i\n", (int)(motor.Ua*1000), (int)(motor.Ub*1000), (int)(motor.Uc*1000)); break;
case 'c': sprintf(string, "%+5i,%+5i,%+5i\n", (int)(c.a*1000), (int)(c.b*1000), (int)(c.c*1000)); break;
case 'f': sprintf(string, "%+5i,%+5i\n", (int)(f.d*1000), (int)(f.q*1000)); break;
case 'p': sprintf(string, "%i\n", (int)servoPulse); break;
case 't': sprintf(string, "%i\n", (int)target); break;
default: string[0] = 0;
}
if(string[0]) Serial.print(string);
}
SerialComm();
}
void SerialComm()
{
switch(Serial.read())
{
case '!': delay(2); printVariable = Serial.available() ? Serial.read() : 0; break;
case 's': Serial.print("shaft_velocity "); Serial.println(motor.shaft_velocity); break;
case 'a': Serial.print("shaft_angle "); Serial.println(motor.shaft_angle); break;
case 'h': Serial.print("Temperature "); Serial.println(GetTemperature()); break;
case 'b': Serial.print("Bus voltage "); Serial.println(GetBusVoltage()); break;
case 'N': motor.controller = (MotionControlType)(int)Serial.parseInt(); Serial.print("Set ");
case 'n': Serial.print("controller "); Serial.println(motor.controller); break;
case 'M': motor.foc_modulation = (FOCModulationType)Serial.parseInt(); Serial.print("Set ");
case 'm': Serial.print("foc_modulation "); Serial.println(motor.foc_modulation); break;
case 'Q': motor.torque_controller = (TorqueControlType)Serial.parseInt(); Serial.print("Set ");
case 'q': Serial.print("torque_controller "); Serial.println(motor.torque_controller); break;
case 'K': motor.KV_rating = Serial.parseFloat();
lemming.flux_linkage = 60 / ( _SQRT3 * _PI * motor.KV_rating * motor.pole_pairs * 2);
Serial.print("Set ");
case 'k': Serial.print("KV_rating "); Serial.println(motor.KV_rating); break;
case 'R': motor.phase_resistance = Serial.parseFloat(); Serial.print("Set ");
case 'r': Serial.print("phase_resistance "); Serial.println(motor.phase_resistance); break;
case 'L': motor.phase_inductance = Serial.parseFloat(); Serial.print("Set ");
case 'l': Serial.print("phase_inductance "); Serial.println(motor.phase_inductance); break;
case 'Z': motor.zero_electric_angle = Serial.parseFloat(); Serial.print("Set ");
case 'z': Serial.print("zero_electric_angle "); Serial.println(motor.zero_electric_angle); break;
case 'T': target = Serial.parseFloat(); Serial.print("Set target "); Serial.println(target); break;
case 't': Serial.print("target "); Serial.println(target); break;
case 'U': driver.voltage_power_supply = Serial.parseFloat(); Serial.print("Set ");
case 'u': Serial.print("voltage_power_supply "); Serial.println(driver.voltage_power_supply); break;
case 'V': motor.voltage_limit = motor.PID_current_q.limit = motor.PID_current_d.limit = Serial.parseFloat(); Serial.print("Set ");
case 'v': Serial.print("voltage_limit "); Serial.println(motor.voltage_limit); break;
case 'C': motor.current_limit = motor.PID_velocity.limit = Serial.parseFloat(); Serial.print("Set ");
case 'c': Serial.print("current_limit "); Serial.println(motor.current_limit); break;
case 'O': motor.PID_velocity.output_ramp = Serial.parseFloat(); Serial.print("Set ");
case 'o': Serial.print("PID_velocity.output_ramp "); Serial.println(motor.PID_velocity.output_ramp); break;
case 'F': motor.LPF_velocity.Tf = Serial.parseFloat(); Serial.print("Set ");
case 'f': Serial.print("LPF_velocity.Tf "); Serial.println(motor.LPF_velocity.Tf); break;
case 'E': motor.LPF_angle.Tf = Serial.parseFloat(); Serial.print("Set ");
case 'e': Serial.print("LPF_angle.Tf "); Serial.println(motor.LPF_angle.Tf); break;
case 'P': motor.PID_velocity.P = Serial.parseFloat(); Serial.print("Set ");
case 'p': Serial.print("PID_velocity.P "); Serial.println(motor.PID_velocity.P); break;
case 'I': motor.PID_velocity.I = Serial.parseFloat(); Serial.print("Set ");
case 'i': Serial.print("PID_velocity.I "); Serial.println(motor.PID_velocity.I); break;
case 'D': motor.PID_velocity.D = Serial.parseFloat(); Serial.print("Set ");
case 'd': Serial.print("PID_velocity.D "); Serial.println(motor.PID_velocity.D); break;
case 'W': motor.P_angle.P = Serial.parseFloat(); Serial.print("Set ");
case 'w': Serial.print("P_angle.P "); Serial.println(motor.P_angle.P); break;
}
}