Proper low cost FOC supporting boards are very hard to find these days and even may not exist. The reason may be that the hobby community has not yet dug into it properly. Therefore this is the attempt to demistify the Field Oriented Control (FOC) algorithm and make a robust but simple implementation for usage with Arduino hadrware.
- Low cost applications <50$
- Low current operation < 5A
- Simple usage and scalability (Arduino) and demistify FOC control in a simple way.
For minimal version of the code more suitable for experimenting please visit the minimal branch.
Odroid | Trinamic |
---|---|
✔️ Open Source | ❌ Open Source |
✔️Simple to use | ✔️ Simple to use |
❌ Low cost ($100) | ❌ Low cost ($100) |
❌ Low power (>50A) | ✔️ Low power |
Infineon | FOC-Arduino-Brushless |
---|---|
❌ Open Source | ✔️ Open Source |
✔️Simple to use | ❌ Simple to use |
✔️Low cost ($40) | ✔️ Low cost |
✔️ Low power | ✔️ Low power |
- Brushless DC motor - 3 pahse (IPower GBM4198H-120T Ebay)
- Encoder - ( Incremental 2400cpr Ebay)
- Arduino + BLDC motor driver ( L6234 driver Drotek, Ebay)
Alternatively the library supports the arduino based gimbal controllers such as:
- HMBGC V2.2 (Ebay)
At this moment we are developing an open source version of Arduin shiled specifically for FOC motor control. We already have prototypes of the board and we are in the testing phase. We will be coming out with the details very soon!
- Plug and play capability with the Arduino Simple FOC library
- Price in the range of $20-$40
- Gerber files and BOM available Open Source
Let me know if you are interested! [email protected] You can explore the 3D model of the board in the PDF form.
The code is simple enough to be run on Arudino Uno board.
- Encoder channels
A
andB
are connected to the Arduino's external intrrupt pins2
and3
. - Optionally if your encoder has
index
signal you can connect it to any available pin, figure shows pin4
.
- The library doesnt support the Index pin for now (version v1.0)
- Connected to the arduino pins
9
,10
and11
. - Additionally you can connect the
enable
pin to the any digital pin of the arduino the picture shows pin8
but this is optional. You can connect the driver enable directly to 5v. - Make sure you connect the common ground of the power supply and your Arduino
- Motor phases
a
,b
andc
are connected directly to the driver outputs
Motor phases a
,b
,c
and encoder channels A
and B
have to be oriented right for the algorightm to work. But don't worry about it too much. Connect it in initialy as you wish and then if it doesnt move reverse pahse a
and b
of the motor, that should be enogh.
To use HMBGC controller for vector control (FOC) you need to connect motor to one of the motor terminals and connect the Encoder. The shema of connection is shown on the figures above, I also took a (very bad) picture of my setup.
Since HMBGC doesn't have acces to the arduinos external interrupt pins 2
and 3
and additionally we only have acces to the analog pins, we need to read the encoder using the software interrupt. To show the functionallity we provide one example of the HMBGC code (HMBGC_example.ino
) using the PciManager library.
- Encoder channels
A
andB
are connected to the pinsA0
andA1
. - Optionally if your encoder has
index
signal you can connect it to any available pin, figure shows pinA2
.
- The library doesnt support the Index pin for now (version v1.0)
- Motor phases
a
,b
andc
are connected directly to the driver outputs
Motor phases a
,b
,c
and encoder channels A
and B
have to be oriented right for the algorightm to work. But don't worry about it too much. Connect it in initialy as you wish and then if it doesnt move reverse pahse a
and b
of the motor, that should be enogh.
The code is organised into a librarie. The library contains two classes BLDCmotor
and Endcoder
. BLDCmotor
contains all the necessary FOC algorithm funcitons as well as PI controllers for the velocity and angle control. Encoder
deals with the encoder interupt funcitons, calcualtes motor angle and velocity( using the Mixed Time Frequency Method).
To initialise the encoder you need to provide the encoder A
and B
channel pins, encoder PPR
and optionally index
pin.
// Encoder(int encA, int encB , int cpr, int index)
// - encA, encB - encoder A and B pins
// - ppr - impulses per rotation (cpr=ppr*4)
// - index pin - (optional input)
Encoder encoder = Encoder(2, 3, 8192, 4);
Additionally the encoder has one more important parameters which is whether you want to use Arduino's internal pullup or you have external one. That is set by changing the value of the encoder.pullup
variuable. The default value is set to Pullup::EXTERN
// check if you need internal pullups
// Pullup::EXTERN - external pullup added - dafault
// Pullup::INTERN - needs internal arduino pullup
encoder.pullup = Pullup::EXTERN;
Finally to start the encoder counter and intialise all the periphery pins you need the call of encoder.init()
is made.
// initialise encoder hardware
encoder.init(doA, doB);
Where the functions doA()
and doB()
are buffering functions of encoder callback funcitons encoder.handleA()
and encoder.handleB()
.
// interrupt ruotine intialisation
void doA(){encoder.handleA();}
void doB(){encoder.handleB();}
You can name the funcitons as you wish. It is just important to supply them to the encoder.init()
funciton. This procedure is a tradeoff in between scalability and simplicity. This allows you to have more than one encoder connected to the same arduino. All you need to do is to instantiate new Encoder
class and create new buffer functions. For example:
// encoder 1
Encoder enc1 = Encoder(2, 3, 8192, 4);
void doA1(){enc1.handleA();}
void doB1(){enc1.handleB();}
// encoder 2
Encoder enc2 = Encoder(5, 6, 8192, 7);
void doA2(){enc2.handleA();}
void doB2(){enc2.handleB();}
void setup(){
...
enc1.init(doA1,doB1);
enc2.init(doA2,doB2);
...
}
To explore better the encoder algorithm an example is provided encoder_example.ino
.
To intialise the motor you need to input the pwm
pins, number of pole pairs
and optionally driver enable
pin.
// BLDCMotor( int phA, int phB, int phC, int pp, int en)
// - phA, phB, phC - motor A,B,C phase pwm pins
// - pp - pole pair number
// - enable pin - (optional input)
BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8);
To finalise the motor setup the encoder is added to the motor and the init
function is called.
// link the motor to the sensor
motor.linkEncoder(&encoder);
// intialise motor
motor.init();
First thing you can configure is your power_supply_voltage
value. The default value is set to 12V
. If you set your power supply to some other vlaue, chnage it here for the control loops to adapt.
// power supply voltage
motor.power_supply_voltage = 12;
You can also change driver type by changing the value of the variable motor.driver
. It tells the algorithm to generate unipolar of bipolar FOC voltages. This basically means if your BLDC driver can only output voltages in range [0,power_supply_voltage]
your driver is DriverType::unipolar
and if it can output voltage in range [-power_supply_voltage, power_supply_voltage]
than you driver is DriverType::bipolar
what is case in most of the drivers and what is default value as well.
// set driver type
// DriverType::unipolar // HMBGC
// DriverType::bipolar // L6234 (default)
motor.driver = DriverType::bipolar;
First parameter you can change is the variable you want to control. You set it by changing the motor.controller
variable. If you want to control the motor angle you will set the controller
to ControlType::angle
, if youy seek the DC motor behavior behaviour by controlling the voltage use ControlType::voltage
, if you wish to control motor angular velocity ControlType::velocity
. If you wish to control velocities which are very very slow, typically around ~0.01 rad/s you can use the ControlType::velocity_ultra_slow
controller.
// set FOC loop to be used
// ControlType::voltage
// ControlType::velocity
// ControlType::velocity_ultra_slow
// ControlType::angle
motor.controller = ControlType::angle;
This control loop allows you to run the BLDC motor as it is simple DC motor using Park transformation. This mode is enabled by:
// voltage control loop
motor.controller = ControlType::voltage;
You rcan test this algoithm by running the example voltage_control.ino
.
The FOC algorithm reads the angle
This control loop will give you the motor which spins freely with the velocity depending on the voltage
$U_q$ you set and the disturbance it is facing. It will turn slower if you try to hold it.
This control loop allows you to spin your BLDC motor with desired velocity. This mode is enabled by:
// velocity control loop
motor.controller = ControlType::velocity;
You can test this algorithm by running the example velocity_control.ino
and velocity_control_serial.ino
.
The velocity control is created by adding a PI velocity controller. This controller reads the motor velocity
To change the parameters of your PI controller to reach desired behaiour you can change motor.PI_velocity
structure:
// velocity PI controller parameters
// default K=1.0 Ti = 0.003
motor.PI_velocity.K = 1;
motor.PI_velocity.Ti = 0.003;
motor.PI_velocity.u_limit = 12;
The parameters of the PI controller are proportional gain K
, integral time constant Ti
and voltage limit u_limit
which is by default set to the power_supply_voltage
.
- The
u_limit
parameter is intended if some reason you wish to limit the voltage that can be sent to your motor. - In general by raising the proportional constant
K
your motor controller will be more reactive, but too much will make it unstable. - The same goes for integral time constant
Ti
the smaller it is the faster motors reaction to disturbance will be, but too small value will make it unstable.
So in order to get optimal performance you will have to fiddle a bit with with the parameters. :)
This control loop allows you to move your BLDC motor to the desired angle in real time. This mode is enabled by:
// angle control loop
motor.controller = ControlType::angle;
You can test this algorithm by running the example angle_control.ino
and angle_control_serial.ino
.
The angle control loop is done by adding one more control loop in cascade on the velocity control loop like showed on the figure above. The loop is closed by using simple P controller. The controller reads the angle
To tune this control loop you can set the parameters to both angle P controller and velocity PI controller.
// velocity PI controller parameters
// default K=1.0 Ti = 0.003
motor.PI_velocity.K = 0.5;
motor.PI_velocity.Ti = 0.01;
motor.PI_velocity.u_limit = 12;
// angle P controller
// default K=70
motor.P_angle.K = 20;
// maximal velocity of the poisition control
// default 20
motor.P_angle.velocity_limit = 10;
It is important to paramter both velocity PI and angle P controller to have the optimal performance.
The velocity PI controller is parametrisized by updating the motor.PI_velcity
structure as expalined before.
- Rough rule should be to lower the proportional gain
K
and raise time constantTi
in order to achieve less vibrations.
The angle P controller can be updated by changign the motor.P_angle
structure.
- Roughly proportional gain
K
will make it more responsive, but too high value will make it unstable.
Additionally you can configure the velocity_limit
value of the controller. This value prevents the contorller to set too high velocities
- If you make your
velocity_limit
very low your motor will be moving in between desired positions with exactly this velocity. If you keep it high, you will not notice that this variable even exists. :D
Finally, each application is a bit different and the chances are you will have to tune the controller values a bit to reach desired behaviour.
This control loop allows you to spin your BLDC motor with desired velocity as well as the velocity loop but it is intended for very smooth operation in very low velocityes (< 0.1 rad/s). This mode is enabled by:
// velocity ultra slow control loop
motor.controller = ControlType::velocity_ultra_slow;
You can test this algorithm by running the example velocity_ultrasloaw_control_serial.ino
.
This type of the velocity control is nothing more but motor angle control. It works particularly well for the purposes of very slow movements because regular velocity calculation techniques are not vel suited for this application and regular velocity control loop would not work well.
The behavior is achieved by integrating the user set target velocity
To change the parameters of your PI controller to reach desired behaiour you can change motor.PI_velocity
structure:
// velocity PI controller parameters
// default K=120.0 Ti = 100.0
motor.PI_velocity_ultra_slow.K = 120;
motor.PI_velocity_ultra_slow.Ti = 100;
motor.PI_velocity_ultra_slow.u_limit = 12;
The parameters of the PI controller are proportional gain K
, integral time constant Ti
and voltage limit u_limit
which is by default set to the power_supply_voltage
.
- The
u_limit
parameter is intended if some reason you wish to limit the voltage that can be sent to your motor. - In general by raising the proportional constant
K
your motor controller will be more reactive, but too much will make it unstable. - The same goes for integral time constant
Ti
the smaller it is the faster motors reaction to disturbance will be, but too small value will make it unstable. By defaualt the integral time constantTi
is set100s
. Which means that it is extreamply slow, meaning that it is not effecting the behvior of the controlle, making it basically a P controller.
From the PI controller parameters you can see that the values are much higher than in the velocity control loop. The reason is because the angle control loop is not the main loop and we need it to follow the profile as good as possible as fast as possible. Therefore we need much higher gain than before.
After the motor and encoder are intialised and the driver and control loops are configured you intialise the FOC algorithm.
// align encoder and start FOC
motor.initFOC();
This function aligns encoder and motor zero positions and intialises FOC variables. It is intended to be run in the setup
function of the Arudino. After the call of this funciton FOC is ready to start following your instructions.
The real time execution of the Arduino Simple FOC library is govenred by two funcitons motor.loopFOC()
and motor.move(float target)
.
// iterative state calculation calculating angle
// and setting FOC pahse voltage
// the faster you run this funciton the better
// in arduino loop it should have ~1kHz
// the best would be to be in ~10kHz range
motor.loopFOC();
The funciton loopFOC()
gets the current motor angle from the encoder, turns in into the electrical angle and computes Clarke transfrom to set the desired
- The faster you can run this funciton the better
- In the empty arduino loop it runs at ~1kHz but idealy it would be around ~10kHz
// iterative function setting the outter loop target
// velocity, position or voltage
// this funciton can be run at much lower frequency than loopFOC funciton
// it can go as low as ~50Hz
motor.move(target);
The move()
method executes the control loops of the algorihtm. If is governed by the motor.controller
variable. It executes eigther pure voltage loop, velocity loop, angle loop or ultra slow velocity loop.
It receives one parameter BLDCMotor::move(float target)
which is current user define target value.
- If the user runs velocity loop,
move
funciton will interprettarget
as the target velocity$\textsf{v}_d$ . - If the user runs angle loop,
move
will interprettarget
parameter as the target angle$\textsf{a}_d$ . - If the user runs the voltage loop,
move
funciton will interpret thetarget
parameter as voltage$\textbf{u}_q$ .
At this point because we are oriented to simplicity we did not implement synchornious version of this code. Uing timer interrupt. The main reason for the moment is that Arduino UNO doesn't have enough timers to run it. But in future we are planning to include this functionality.
Examples folder structure
├───examples
│ ├───voltage_control # example of the voltage control loop with configuraiton
│ ├───angle_control # example of angle control loop with configuraiton
│ ├───angle_control_serial # example of angle control using serial port with configuraiton
│ ├───velocity_control # example of velocity control loop with configuraiton
│ ├───velocity_control_serial # example of velocity control using serial port with configuraiton
│ ├───velocity_ultraslow_control_serial # example of ultra slow velocity control using serial port with configuraiton
│ ├───encoder_example # simple example of encoder usage
│ ├───minimal_example # example of code without using configuration
│ └───HMBGC_example # example of code to be used with HMBGC controller with configuraiton
To debug control loop exection in the examples we added a funciton motor_monitor()
which log the motor variables to the serial port. The funciton logs different variables based for differenc control loops.
// utility function intended to be used with serial plotter to monitor motor variables
// significantly slowing the execution down!!!!
void motor_monitor() {
switch (motor.controller) {
case ControlType::velocity_ultra_slow:
case ControlType::velocity:
Serial.print(motor.voltage_q);
Serial.print("\t");
Serial.print(motor.shaft_velocity_sp);
Serial.print("\t");
Serial.println(motor.shaft_velocity);
break;
case ControlType::angle:
Serial.print(motor.voltage_q);
Serial.print("\t");
Serial.print(motor.shaft_angle_sp);
Serial.print("\t");
Serial.println(motor.shaft_angle);
break;
case ControlType::voltage:
Serial.print(motor.voltage_q);
Serial.print("\t");
Serial.println(motor.shaft_velocity);
break;
}
}
This is just a template funciton to help you debug and create your own functions in future. The funciton accesses the motor variables:
class BLDCMotor
{
public:
...
// current elelctrical angle
float elctric_angle;
// current motor angle
float shaft_angle;
// current motor velocity
float shaft_velocity;
// current target velocity
float shaft_velocity_sp;
// current target angle
float shaft_angle_sp;
// current voltage u_q set
float voltage_q;
...
}
Additionally it is possible to use encoder api directly to get the encoder angle and velocity.
class Encoder{
public:
// shaft velocity getter
float getVelocity();
// shaft angle getter
float getAngle();
}
- Proper introduction of the Arudino FOC Shield V1.2
- Make the library accesible in the Arduino Library Manager
- Publish a video utilising the library and the samples
- Make minimal version of the arduino code - all in one arduino file
- Encoder index proper implementation
- Enable more dirver types
- Timer interrupt execution rather than in the
loop()
- Make support for magnetic encoder AS5048 and similar