I have a problem with my motor control especially in terms of velocity control. I already implemented velocity control and angle control and now i have bought a new motor and suddenly to code which was working fine isn‘t working anymore.
Therefore i tried to use torque control with my new motor and this was working perfectly fine while using angle control wouldn‘t work. When I use angle control or velocity control my motor isn‘t spinning at all. Is there maybe a problem with my parameters of my PID regelator? As mentioned before I already inplemented velocity and angle control with a other motor.
I tried to re-tune the PID gains but I can’t figure out the perfect gains.
My motor requiers currents about 600mA and the motor I used before also needed about 600mA. The motor I used before was a maxon ec flat and currently I am using a Nanotec DB28S01.
Current sensing is in my application not available.
As far as I could find, Nanotec DB28S01 has relatively high phase resistance of around 8 Ohm. While es flat are usually lower resistance, but of course that all depends on the exact motor parameters.
Could we see your code maybe? It would help to debug.
Are you using the same sensor for both motors and the same MCU?
What is the exact behavior that you have once you use the velocity control, the motor does not move at all? No noise? No vibration?
The motor starts to vibrate but isn’t spinning. I am currently using the ESP32 an hall sensors as I also did with my other motor.
Here is my code:
#include <SimpleFOC.h
int U_EN = 18; // inhu
int V_EN = 5; // inhv
int W_EN = 17; // inhw
float target_velocity = 0;
// Motor instance
BLDCMotor motor = BLDCMotor(2);
// driver instance
BLDCDriver3PWM driver = BLDCDriver3PWM(16, 4, 32);
HallSensor sensor = HallSensor(25, 26, 27, 2);
// Interrupt routine initialization
// channel A, B and C callbacks
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}
// instantiate the commander
Commander command = Commander(Serial);
void doTarget(char* cmd) { command.scalar(&target_velocity, cmd); }
void setup() {
pinMode(U_EN, OUTPUT);
pinMode(V_EN, OUTPUT);
pinMode(W_EN, OUTPUT);
digitalWrite(U_EN, HIGH);
digitalWrite(V_EN, HIGH);
digitalWrite(W_EN, HIGH);
Serial.begin(115200);
SimpleFOCDebug::enable(&Serial);
// initialize sensor hardware
sensor.init();
// hardware interrupt enable
sensor.enableInterrupts(doA, doB, doC);
// link the motor and the sensor
motor.linkSensor(&sensor);
// driver config
// power supply voltage [V]
driver.voltage_power_supply = 12;
// driver init
if(!driver.init()){
Serial.println("Driver init failed!");
return;
}
// link driver
motor.linkDriver(&driver);
// set motion control loop to be used
motor.controller = MotionControlType::velocity;
// aligning voltage [V]
motor.voltage_sensor_align = 2.2f;
// contoller configuration
// default parameters in defaults.h
// velocity PI controller parameters
motor.PID_velocity.P = 0.1f;
motor.PID_velocity.I = 0.1f;
motor.PID_velocity.D = 0;
// default voltage_power_supply
motor.voltage_limit = 12;
// default value is 300 volts per sec ~ 0.3V per millisecond
motor.PID_velocity.output_ramp = 300;
// velocity low pass filtering time constant
motor.LPF_velocity.Tf = 0.01f;
// 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");
Serial.println(F("Motor ready."));
Serial.println(F("Set the target velocity using serial terminal:"));
_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_velocity);
// function intended to be used with serial plotter to monitor motor variables
// significantly slowing the execution down!!!!
// motor.monitor();
// user communication
command.run();
}
Thank you very much increasing the velocity filtering values was the solution for my problem!
But I have another question: How can I achieve higher speeds for my angle control?
This is my current code:
#include <SimpleFOC.h>
int U_EN = 18; // inhu
int V_EN = 5; // inhv
int W_EN = 17; // inhw
float target_angle = 0; //= 6.28;
// Motor instance(pp)
BLDCMotor motor = BLDCMotor(2);
// driver instance
BLDCDriver3PWM driver = BLDCDriver3PWM(16, 4, 32);
HallSensor sensor = HallSensor(25, 26, 27, 2);
// Interrupt routine initialization
// channel A, B and C callbacks
void doA(){sensor.handleA();}
void doB(){sensor.handleB();}
void doC(){sensor.handleC();}
// instantiate the commander
Commander command = Commander(Serial);
void doTarget(char* cmd) { command.scalar(&target_angle, cmd); }
void setup() {
pinMode(U_EN, OUTPUT);
pinMode(V_EN, OUTPUT);
pinMode(W_EN, OUTPUT);
digitalWrite(U_EN, HIGH);
digitalWrite(V_EN, HIGH);
digitalWrite(W_EN, HIGH);
Serial.begin(115200);
SimpleFOCDebug::enable(&Serial);
// initialize sensor hardware
sensor.init();
// hardware interrupt enable
sensor.enableInterrupts(doA, doB, doC);
// link the motor and the sensor
motor.linkSensor(&sensor);
// driver config
// power supply voltage [V]
driver.voltage_power_supply = 12;
// driver init
if(!driver.init()){
Serial.println("Driver init failed!");
return;
}
// link driver
motor.linkDriver(&driver);
// aligning voltage
motor.voltage_sensor_align = 2.2f;
// set motion control loop to be used
motor.controller = MotionControlType::angle;
// contoller configuration
// default parameters in defaults.h
// velocity PI controller parameters
motor.PID_velocity.P = 0.2f;
motor.PID_velocity.I = 0.20f;
motor.PID_velocity.D = 0;
// default voltage_power_supply
motor.voltage_limit = 12;
// default value is 300 volts per sec ~ 0.3V per millisecond
motor.PID_velocity.output_ramp = 1000;
// velocity low pass filtering time constant
motor.LPF_velocity.Tf = 0.1f;
// angle P controller
motor.P_angle.P = 10;
// acceleration control using output ramp
// this variable is in rad/s^2 and sets the limit of acceleration
motor.P_angle.output_ramp = 10000;
// maximal velocity of the position control
motor.velocity_limit = 40;
// use monitoring with serial
Serial.begin(115200);
// 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 angle");
Serial.println(F("Motor ready."));
Serial.println(F("Set the target angle using serial terminal:"));
_delay(1000);
}
void loop() {
// main FOC algorithm function
motor.loopFOC();
// Motion control function
// You can also use motor.move() and set the motor.target in the code
motor.move(target_angle);
// function intended to be used with serial plotter to monitor motor variables
// significantly slowing the execution down!!!!
// motor.monitor();
// user communication
command.run();
}