I have two decently sized motor (3A) with hall sensors being driven from two DRV8316 driven by an ESP32-S3.
So far I’ve been able to get things up and running for the most part, but I’m running into an issue where the velocity seems to be capped at around 1050 rpm no matter what I set the driver voltage limit or motor voltage limit to.
I’m not pulling too much power and the motor will run about 20k rpm off an amazon driver board (one of those things with a pot to set the speed) so I don’t think that it’s a motor or power issue. It feels to me like I’m doing something silly in software.
From a quick search of the forums it seems like most of the time that other folks have this issue it’s their encoders which are limiting the max speed, but that shouldn’t be an issue with hall sensors right?
Here’s how my code is set up now:
// Closed loop motor control example for two motors
#include <SimpleFOC.h>
// BLDC motor & driver instances
BLDCMotor motor1 = BLDCMotor(1);
BLDCDriver3PWM driver1 = BLDCDriver3PWM(47, 45, 35);
BLDCMotor motor2 = BLDCMotor(1);
BLDCDriver3PWM driver2 = BLDCDriver3PWM(37, 39, 41);
HallSensor sensor1 = HallSensor(4, 5, 6, 1);
HallSensor sensor2 = HallSensor(7, 15, 16, 1);
// Interrupt routine intialisation
// channel A, B and C callbacks
void doA1(){sensor1.handleA();}
void doB1(){sensor1.handleB();}
void doC1(){sensor1.handleC();}
void doA2(){sensor2.handleA();}
void doB2(){sensor2.handleB();}
void doC2(){sensor2.handleC();}
// target variables
float target_velocity = 0;
void setup() {
// Enable pin for the drivers...LOW is on
pinMode(18, OUTPUT);
digitalWrite(18, LOW);
//Enable sensors
sensor1.init();
sensor1.enableInterrupts(doA1, doB1, doC1); // Enable hardware interrupts for all channels
sensor2.init();
sensor2.enableInterrupts(doA2, doB2, doC2); // Enable hardware interrupts for all channels
// link the motor to the sensor
motor1.linkSensor(&sensor1);
motor2.linkSensor(&sensor2);
// use monitoring with serial
Serial.begin(115200);
// enable more verbose output for debugging
// comment out if not needed
SimpleFOCDebug::enable(&Serial);
// driver1 config
driver1.voltage_power_supply = 28;
driver2.voltage_power_supply = 28;
driver1.voltage_limit = 10;
driver2.voltage_limit = 10 ;
// limiting motor movements
motor1.voltage_limit = 7; // [V]
motor2.voltage_limit = 7; // [V]
driver1.init();
driver2.init();
// link the motors and the drivers
motor1.linkDriver(&driver1);
motor2.linkDriver(&driver2);
// aligning voltage [V]
motor1.voltage_sensor_align = 0.35;
motor2.voltage_sensor_align = 0.35;
// open loop control config
// set motion control loop to be used
motor1.controller = MotionControlType::velocity;
motor2.controller = MotionControlType::velocity;
// velocity PI controller parameters
motor1.PID_velocity.P = 0.002f;
motor1.PID_velocity.I = 0;
motor1.PID_velocity.D = 0;
motor2.PID_velocity.P = 0.002f;
motor2.PID_velocity.I = 0;
motor2.PID_velocity.D = 0;
// jerk control using voltage voltage ramp
// default value is 300 volts per sec ~ 0.3V per millisecond
motor1.PID_velocity.output_ramp = 1000;
motor2.PID_velocity.output_ramp = 1000;
// velocity low pass filtering time constant
motor1.LPF_velocity.Tf = 0.01f;
motor2.LPF_velocity.Tf = 0.01f;
// use monitoring with serial
Serial.begin(115200);
// comment out if not needed
motor1.useMonitoring(Serial);
motor2.useMonitoring(Serial);
// init motor hardware
motor1.init();
motor1.initFOC();
motor2.init();
motor2.initFOC();
Serial.println("Motors ready!");
Serial.println("Set target velocities [rad/s]");
_delay(1000);
}
float maxVelocity = 6000;
float direction = 1.0;
void loop() {
// FOC algorithm function
motor1.loopFOC();
motor2.loopFOC();
// closed loop velocity movement
motor1.move(target_velocity);
motor2.move(target_velocity);
//Slowly ramping up the target velocity
if(random(50) == 0){
target_velocity = target_velocity + 0.3*direction;
Serial.print("Target velocity: ");
Serial.println(target_velocity);
if(target_velocity > maxVelocity){
direction = -1.0;
}
if(target_velocity < -maxVelocity){
direction = 1.0;
}
}
}
In reality, they are different aspects that will prevent your motor from reaching that speed.
PWM Modulation:
Your driver will not reach the supply voltage:
if you limited the driver.voltage_limit
Deadtime is required to prevent shoot throughs, it depends on your hardware with 3PWM and on driver.dead_zone parameter for 6PWM, it will prevent the driver from reaching 100% PWM modulation.
Trapezoidal modes will provide the highest modulation, but are inefficient and noisy.
Space vector modulation will provide a higher modulation than Sinusoidal, thus a higher speed (which one should I use).
With Low side current sensing and FOC, you need to limit the PWM modulation to allow enough Low side mosfet ON time for phase current measurements, which will reduce the speed.
To sum up:
don’t set driver.voltage_limit if your motor can handle the power supply voltage and if you are not using low side current sensing
use Space Vector modulation with the following limit
A higher limit can increase speed but will impact the waveform, generating more noise due to torque ripples.
Sensor alignment:
Sensor alignment will calibrate sensor.zero_offset_angle and might require tweaking.
This will ensure your motor is not running slower in one direction.
Lag compensation:
In voltage mode, lag compensation will compensate for the current vector lag due to the phase inductance (phase resistance, phase inductance and KV are required).
FOC_current mode will achieve the same goal through current sensing (phase resistance
phase inductance and KV are not required).
Loop rate:
The faster your motor should spin, the higher your loop rate should be:
Slow MCUs can limit the loop rate. Prefer a more powerful MCU if you aim for high velocity
The higher pole pairs motors require a higher loop rate
Communication/debug can slow down the loop rate. Downsample monitoring.
Don’t print too often in the loop
Don’t put delays in the loop
Use faster implementation for your sensor (e.g. use STM32HWEncoder with AS5047P encoder)
The faster the motor spins, the more interrupts will be generated with hall sensors. Try running without interrupts by commenting enableinterrupts() statement (from SimpleFOC V2.3.4)
Velocity mode requires more computation than torque mode
FOC_current mode requires more computation than Voltage mode
Every additional motor you drive will divide the loop rate
Those cheapo amazon boards run 8-bit sensorless trapezoidal or hall kind-a-sensored which isn’t exactly the FOC/close loop you can compare SimpleFOC with (or any other foc algo), like comparing an axe with a surgical scalpel and saying why it takes so long to hack my woodpile with the scalpel since it takes a few minutes to chop it with my axe.
I think that there is something funky going on with my setup in terms of how I am configuring the motor.
The reason that I say that is when I command a speed of 300 rads/second the motor actually spins about 450rpm when measured with an external tachometer which is just ~47 rads/sec.
I’m commanding the motor with motor1.move(target_velocity); which is in rads/sec, right?
Any idea which setting I could have messed up to get that wrong?
Thank you! That is super helpful. It seems like 1 pole pair leads to my reported velocity (read with motor1.shaft_velocity) matching my external reading with a tachometer so it seems like 1 is the right value for poles.
Does this seem like a reasonable way to be setting my poles? (Just to make sure I’m not doing something silly and setting the motor poles lower than the hall sensors poles or something like no).
The question then is why is my actual velocity so much lower than my target velocity? The motor does not even begin to spin until the target velocity is over 100 rads/sec. I’m pretty sure that it’s not an issue of lack of power because I can make the motor spin up to 80 rads/sec by increasing the target velocity up to like 1000;
You are probably right. I am having issues with getting things running in torque mode so hopefully I can learn something by figuring out what is going on there. I will keep digging.
I’ve done my best to implement your suggestion of running a single motor in torque/voltage mode with no driver.voltage limit set and and the motor.voltage_limit set as you suggested with svpwm turned on. I am seeing the same behavior of running into a hard ceiling above which I can’t drive the motor faster.
Here is my code copied from the compute Kv example:
/**
*
* Find KV rating for motor with Hall sensors
*
* Motor KV rating is defiend as the increase of the motor velocity expressed in rotations per minute [rpm] per each 1 Volt int voltage control mode.
*
* This example will set your motor in the torque control mode using voltage and set 1 volt to the motor. By reading the velocity it will calculat the motors KV rating.
* - To make this esimation more credible you can try increasing the target voltage (or decrease in some cases)
* - The KV rating should be realatively static number - it should not change considerably with the increase in the voltage
*/
#include <SimpleFOC.h>
// BLDC motor & driver instance
BLDCMotor motor = BLDCMotor(1);
BLDCDriver3PWM driver = BLDCDriver3PWM(47, 45, 35);
// hall sensor instance
HallSensor sensor = HallSensor(4, 5, 6, 1);
// Interrupt routine intialisation
// channel A and B callbacks
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}
// voltage set point variable
float target_voltage = 1;
// instantiate the commander
Commander command = Commander(Serial);
void doTarget(char* cmd) { command.scalar(&target_voltage, cmd); }
void calcKV(char* cmd) {
// calculate the KV
Serial.println(motor.shaft_velocity/motor.target/_SQRT3*30.0f/_PI);
}
//Computes a moving window average of the motor shaft velocity
void computeMovingAverage(){
static float sum = 0;
static int count = 0;
sum += motor.shaft_velocity;
count++;
if(count == 100){
Serial.println(sum/100);
sum = 0;
count = 0;
}
}
void setup() {
pinMode(18, OUTPUT);
digitalWrite(18, LOW);
// use monitoring with serial
Serial.begin(115200);
// enable more verbose output for debugging
// comment out if not needed
SimpleFOCDebug::enable(&Serial);
// initialize encoder sensor hardware
sensor.init();
sensor.enableInterrupts(doA, doB, doC);
// link the motor to the sensor
motor.linkSensor(&sensor);
// driver config
// IMPORTANT!
// make sure to set the correct power supply voltage [V]
driver.voltage_power_supply = 28;
driver.init();
// link driver
motor.linkDriver(&driver);
// aligning voltage
motor.voltage_sensor_align = 1;
motor.foc_modulation = FOCModulationType::SpaceVectorPWM;
motor.voltage_limit = 0.58 * driver.voltage_power_supply;
// set motion control loop to be used
motor.controller = MotionControlType::torque;
// comment out if not needed
motor.useMonitoring(Serial);
// initialize motor
motor.init();
// align sensor and start FOC
motor.initFOC();
// add target command T
command.add('T', doTarget, "target voltage");
command.add('K', calcKV, "calculate KV rating");
Serial.println(F("Motor ready."));
Serial.println(F("Set the target voltage : - commnad T"));
Serial.println(F("Calculate the motor KV : - command K"));
_delay(1000);
}
void loop() {
// main FOC algorithm function
// the faster you run this function the better
// Arduino UNO loop ~1kHz
// Bluepill loop ~10kHz
motor.loopFOC();
// Motion control function
// velocity, position or voltage (defined in motor.controller)
// this function can be run at much lower frequency than loopFOC() function
// You can also use motor.move() and set the motor.target in the code
motor.move(target_voltage);
// user communication
command.run();
static int i = 0;
if(i++ == 100){
i = 0;
computeMovingAverage();
}
}
Could you print your loop speed (for example in the computeMovingAverage function, when printing the average value also print the elapsed time in microseconds)?
When the initFOC runs the calibration, does the motor oscillate a lot or does it settle in place immediately?
Normally for 1PP motors they like to spin very fast, and its hard to calibrate them because they move too far and then don’t settle in time.
I’m getting 61,750Hz on my loop speed computed by adding:
long loopCount = 0;
unsigned long startTime = micros();
void loop() {
//Compute the number of loops every second
loopCount++;
if(micros() - startTime > 1000000){
Serial.println(loopCount);
loopCount = 0;
startTime = micros();
}
I don’t know if I have enough experience to judge this so I made a quick video. Sorry about the background noise: