Running BLDC motor based on BEMF control algorithms is an easy way but it comes to it's limitations if you need torque control in case of low motor speed or you even want to control the motors position - like in servo applications. For those use cases you need a sensor based position feedback of the motors rotor position. This information is used to calculate the the needed current to move or hold the motor in one position.
The sensorWe use a TLE5012B E1000 MS2Go, one of our fast system prototyping boards.To perform the motor control algorithms we need a more powerful controller than the XMC1100 on this Kit so we just use the sensor breakout part (1) of it.
A diametral magnet is located at the end of the motor shaft. The sensor sits next to it with a small air gap of a view millimeter. Therefore sensing is contactless, leads to no friction in the system and no need for maintenance.
Our motor offers a hollow shaft so we 3D printed a holding for a diametral magnet as well as the sensor breakout board.
Done with mechanics, let's move on to electronics.
The sensor is connected to our microcontroller board, a XMC4700 Relax Kit Lite via 3-Wire SPI. As the standard SPI pins (on the Arduino UNO layout) are allocated by our BLDC power shield we use the additional pins provided by the XMC4700 Relax Kit:
#define SS 96 // P0.12
#define MOSI 71 // P3.11 -----> connect 3.11 and 3.12 on the board! (3-Wire SPI)
#define MISO 97 // P3.12
#define SCK 70 // P3.13
The software library to read out the sensor can be found on github.
You can use this code to test the sensor functionality. It will give you the angle in degree (-180° to +180°) via serial communication (115200 baud):
#include <Tle5012b.h>
#include <Tle5012b_reg.h>
Tle5012b_SPI Spi1 = Tle5012b_SPI(2);
Tle5012b_reg Tle5012MagneticAngleSensor = Tle5012b_reg();
#define SS 96 // P0.12
#define MOSI 71 // P3.11 -----> connect 3.11 and 3.12 on the board! (3-Wire SPI)
#define MISO 97 // P3.12
#define SCK 70 // P3.13
double d = 0.0;
void setup() {
Serial.begin(115200);
Tle5012MagneticAngleSensor.begin(Spi1, MISO, MOSI, SCK, SS, Tle5012b::TLE5012B_S0);
}
void loop() {
Tle5012MagneticAngleSensor.getAngleValue(d);
Serial.print("angle:"); Serial.println(d);
delay(10);
}
Power stageThe power stage used for this BLDC application is a BLDC SHIELD IFX007T.It uses three IFX007T smart half bridge ICs. Those can be dis-/enabled and set HIGHSIDE or LOWSIDE active. They offer build in safety features such as short circuit, overcurrent and overtemperature protection. So whenever something goes wrong with them you are on the safe side. Just stack this on top of you controller board and you are ready to go!
Software wise we use standard Arduino functions to implement this shield in our code, no library is needed. You can use the following code, generating three sine waves with 120° phase shift to test the shield:Note: You might have to adjust the "delay" value.
//#define PI (double) 3.14159265359
#define PHASE_DELAY_1 (double) 2.094395102 //120° phase shift
#define PHASE_DELAY_2 (double) 4.188790205 //240° phase shift
const int U = 11;
const int V = 10;
const int W = 9;
const int EN_U = 6;
const int EN_V = 5;
const int EN_W = 3;
double i=0;
int dutycyle = 40; //0-127
double pwmOne = 0;
double pwmTwo = 0;
double pwmThree = 0;
void setup() {
pinMode(U, OUTPUT); setAnalogWriteFrequency(U,10000);
pinMode(V, OUTPUT); setAnalogWriteFrequency(V,10000);
pinMode(W, OUTPUT); setAnalogWriteFrequency(W,10000);
pinMode(EN_U, OUTPUT); digitalWrite(EN_U, HIGH);
pinMode(EN_V, OUTPUT); digitalWrite(EN_V, HIGH);
pinMode(EN_W, OUTPUT); digitalWrite(EN_W, HIGH);
}
void loop() {
pwmOne = 127 + dutycyle * sin(i);
pwmTwo = 127 + dutycyle * sin(i + PHASE_DELAY_1);
pwmThree = 127 + dutycyle * sin(i + PHASE_DELAY_2);
analogWrite(U, pwmOne);
analogWrite(V, pwmTwo);
analogWrite(W, pwmThree);
i+=0.1;
delay(5);
}
The motor will run "uncontrolled" in this example, following a 3-phase field.
If you try to stop the motor by hand in the previous example you will see that this is easily possible. This is because the inducted magnetic field is just moving on, regardless of the rotors position.
As we receive the actual mechanical angle from our sensor we are able to set the three inducting currents in regards to the rotors position. This will enhance the starting behavior and will even lead to the ability to do position control of the motor.
According to the polepairs of our motor several electrical oscillations are needed to perform a full mechanical rotation.Based on the mechanical angle information and number of polepairs the first electical waveform can be calculated bysin(Polepairs*mechanical angle)
Adding two sine waves, 120° and 240° shifted we will end up with the three electric currents representing the actual mechanical position. This mean you can still turn the motor by hand as the currents are constantly updated to this exact mechanical position. Let's call it the 0-position.
To move the motor in a certain direction we need to shift the inducted magnetic field in front or in back of the 0-position.
The electrical waveforms to move the rotor are calculated by
sin(Polepairs*mechanical angle+ phaseshift)
sin(Polepairs*mechanical angle+ phaseshift + 120°)
sin(Polepairs*mechanical angle + phaseshift + 240°)
In the following code example you will also find an "offset" value. This is introduced to calculate the 0-position. The "offset" is affected by the mechanical assembly of our sensor setup and the stator.
The motor control algorithm is called in a fixed time interval in a timer based interrupt called with
void CCU40_0_IRQHandler(void)
The algorithm:
- reads the actual stator position in degrees
- calculates the actual stator position in rad
- calculates the three sine waves according to the actual rotor position
- sets the power stage accordingly
Note: To make this work with your motor you will have to adapt- POLEPAIRS- offset- phaseshift according to your motorSet the POLEPAIRS value according to your motor and change the phaseshift value by "+" and "-" via serial (115200baud) so the motor runs smooth and with minimum current consumption in both directions. Set the offset to be in the middle of these phaseshift values so that you have offset+phaseshift running in one direction and offset-phaseshift running in the other.
#include <Tle5012b.h>
#include <Tle5012b_reg.h>
#define POLEPAIRS 21
#define SS 96 // P0.12
#define MOSI 71 // P3.11 -----> 3.11 und 3.12 zusammenlöten! (3-Wire SPI)
#define MISO 97 // P3.12
#define SCK 70 // P3.13
//#define PI (double) 3.14159265359
#define PHASE_DELAY_1 (double) 2.094395102 //120°
#define PHASE_DELAY_2 (double) 4.188790205 //240°
Tle5012b_SPI Spi1 = Tle5012b_SPI(2);
Tle5012b_reg Tle5012MagneticAngleSensor = Tle5012b_reg();
const int U = 11;
const int V = 10;
const int W = 9;
const int EN_U = 6;
const int EN_V = 5;
const int EN_W = 3;
int duty = 40;
double pwmOne = 0;
double pwmTwo = 0;
double pwmThree = 0;
double angle = 0.0;
float angle_rad = 0.0;
double offset = 0.6;
double PhaseShift = 1.9;
extern "C" {
void CCU40_0_IRQHandler(void)
{ Tle5012MagneticAngleSensor.getAngleValue(angle);
angle_rad = (angle) *((double)2.0*(double)PI/(double)360.0); // Mechanical angle in RAD
pwmOne = 127 + duty*sin(angle_rad*POLEPAIRS + PhaseShift + offset); analogWrite(U, pwmOne);
pwmTwo = 127 + duty*sin(angle_rad*POLEPAIRS + PhaseShift + PHASE_DELAY_1 + offset); analogWrite(V, pwmTwo);
pwmThree = 127 + duty*sin(angle_rad*POLEPAIRS + PhaseShift + PHASE_DELAY_2 + offset); analogWrite(W, pwmThree);
}
}
void setup() {
Serial.begin(115200);
Tle5012MagneticAngleSensor.begin(Spi1, MISO, MOSI, SCK, SS, Tle5012b::TLE5012B_S0);
pinMode(U, OUTPUT); setAnalogWriteFrequency(U,10000);
pinMode(V, OUTPUT); setAnalogWriteFrequency(V,10000);
pinMode(W, OUTPUT); setAnalogWriteFrequency(W,10000);
pinMode(EN_U, OUTPUT); digitalWrite(EN_U, HIGH);
pinMode(EN_V, OUTPUT); digitalWrite(EN_V, HIGH);
pinMode(EN_W, OUTPUT); digitalWrite(EN_W, HIGH);
//Setup Interrupt settings
XMC_CCU4_SLICE_COMPARE_CONFIG_t pwm_config = {0};
pwm_config.passive_level = XMC_CCU4_SLICE_OUTPUT_PASSIVE_LEVEL_HIGH;
pwm_config.prescaler_initval = XMC_CCU4_SLICE_PRESCALER_128;
//Setup interrupt1
XMC_CCU4_Init(CCU40, XMC_CCU4_SLICE_MCMS_ACTION_TRANSFER_PR_CR);
XMC_CCU4_SLICE_CompareInit(CCU40_CC43, &pwm_config);
XMC_CCU4_EnableClock(CCU40, 3);
XMC_CCU4_SLICE_SetTimerPeriodMatch(CCU40_CC43, 200); // Adjust last Value or Prescaler
/* Enable compare match and period match events */
XMC_CCU4_SLICE_EnableEvent(CCU40_CC43, XMC_CCU4_SLICE_IRQ_ID_PERIOD_MATCH);
/* Connect period match event to SR0 */
XMC_CCU4_SLICE_SetInterruptNode(CCU40_CC43, XMC_CCU4_SLICE_IRQ_ID_PERIOD_MATCH, XMC_CCU4_SLICE_SR_ID_0);
/* Configure NVIC */
/* Set priority */
NVIC_SetPriority(CCU40_0_IRQn, 10);
/* Enable IRQ */
NVIC_EnableIRQ(CCU40_0_IRQn);
XMC_CCU4_EnableShadowTransfer(CCU40, (CCU4_GCSS_S0SE_Msk << (4 * 3)));
XMC_CCU4_SLICE_StartTimer(CCU40_CC43);
}
void loop() {
// put your main code here, to run repeatedly:
while (Serial.available() != 0)
{
int input = 0;
input = Serial.read();
if(input == 43)
{
PhaseShift+=0.01;
Serial.print("\t\t");
Serial.println(PhaseShift);
}
if(input == 45)
{
PhaseShift-=0.01;
Serial.print("\t\t");
Serial.println(PhaseShift);
}
}
}
Congrats! Your motor runs in sensored mode now.
Your motor will spin now and can't be hold easily as the torque vector is always in the right place.
Motor control (advanced)You might notice that the motor is still moving a bit rough (checking the current meter).An "ideal" motor would show equally arranged coils thus showing the same distance across a mechanical rotation. The real motor shows small differences from coil to coil.Below you see a chart that compares the real (measured) values with an pure sine wave.
The real values oscillate around the ideal sine wave. This is what can be seen in the current drawn.
To solve this we use our power stage example code to run the motor along three pure sine waves while we save the actual mechanical angle accordingly. Both will be saved in an integer array for each phase:int PWMvalues[mechanical angle] = PWM value at this angle
Once this three arrays are collected we use it the other way around, using the actual angle and looking for the corresponding PWM values U, V, W in the arrays.
The following code will:
- run the motor uncontrolled
- collect the arrays for U, V, W
- print the arrays via the serial port (115200baud)
- run the motor in a controlled way
#include <Tle5012b.h>
#include <Tle5012b_reg.h>
#define POLEPAIRS 21
#define SS 96 // P0.12
#define MOSI 71 // P3.11 -----> 3.11 und 3.12 zusammenlöten! (3-Wire SPI)
#define MISO 97 // P3.12
#define SCK 70 // P3.13
//#define PI (double) 3.14159265359
#define PHASE_DELAY_1 (double) 2.094395102 //120°
#define PHASE_DELAY_2 (double) 4.188790205 //240°
Tle5012b_SPI Spi1 = Tle5012b_SPI(2);
Tle5012b_reg Tle5012MagneticAngleSensor = Tle5012b_reg();
const int U = 11;
const int V = 10;
const int W = 9;
const int EN_U = 6;
const int EN_V = 5;
const int EN_W = 3;
int i=0;
int duty = 40;
int pwmOne = 0;
int pwmTwo = 0;
int pwmThree = 0;
double amplitudeOne;
double amplitudeTwo;
double amplitudeThree;
double angle = 0.0;
float angle_rad = 0.0;
int myPWM_U_values[3600];
int myPWM_V_values[3600];
int myPWM_W_values[3600];
int myPWM_U_values_save[3600];
int myPWM_V_values_save[3600];
int myPWM_W_values_save[3600];
int offset = -22;
int PhaseShift = 44;
bool share = 1;
int n = 0;
int m = 0;
int l = 0;
extern "C" {
void CCU40_0_IRQHandler(void)
{
//run motor uncontrolled
if(millis()<5000){
angle_rad += 0.02;
pwmOne = 100*sin(angle_rad);
pwmTwo = 100*sin(angle_rad + PHASE_DELAY_1);
pwmThree = 100*sin(angle_rad + PHASE_DELAY_2);
analogWrite(U, 127 + duty*pwmOne/100);
analogWrite(V, 127 + duty*pwmTwo/100);
analogWrite(W, 127 + duty*pwmThree/100);
Tle5012MagneticAngleSensor.getAngleValue(angle);
int angle_out = (angle+180)*10; //0-3600
int pwm_U_out = pwmOne; //-100-100
int pwm_V_out = pwmTwo; //-100-100
int pwm_W_out = pwmThree; //-100-100
//save arrays
if(millis()>2000){
myPWM_U_values[angle_out] = pwm_U_out;
myPWM_V_values[angle_out] = pwm_V_out;
myPWM_W_values[angle_out] = pwm_W_out;
}
}
//print PWM_U
if(millis()> 5000 && n <= 3599){
myPWM_U_values_save[n] = myPWM_U_values[n];
Serial.print(myPWM_U_values[n]); Serial.print(", ");
n++;
if(n == 3600){Serial.println();
}
}
//print PWM_V
if(millis()> 10000 && m <= 3599){
myPWM_V_values_save[m] = myPWM_V_values[m];
Serial.print(myPWM_V_values[m]); Serial.print(", ");
m++;
if(m == 3600){Serial.println();
}
}
//print PWM_W
if(millis()> 15000 && l <= 3599){
myPWM_W_values_save[l] = myPWM_W_values[l];
Serial.print(myPWM_W_values[l]); Serial.print(", ");
l++;
if(l == 3600){Serial.println();
}
}
// run motor controlled
if(millis()> 20000){
Tle5012MagneticAngleSensor.getAngleValue(angle);
int angle_table = (angle+180)*10+PhaseShift+offset;
if (angle_table >= 3600) {angle_table -=3600;}
if (angle_table < 0000) {angle_table +=3600;}
pwmOne = myPWM_U_values_save[angle_table];
pwmTwo = myPWM_V_values_save[angle_table];
pwmThree = myPWM_W_values_save[angle_table];
analogWrite(U, 127 + duty*pwmOne/100);
analogWrite(V, 127 + duty*pwmTwo/100);
analogWrite(W, 127 + duty*pwmThree/100);
}
}
}
void setup() {
Serial.begin(115200);
Tle5012MagneticAngleSensor.begin(Spi1, MISO, MOSI, SCK, SS, Tle5012b::TLE5012B_S0);
pinMode(U, OUTPUT); setAnalogWriteFrequency(U,10000);
pinMode(V, OUTPUT); setAnalogWriteFrequency(V,10000);
pinMode(W, OUTPUT); setAnalogWriteFrequency(W,10000);
pinMode(EN_U, OUTPUT); digitalWrite(EN_U, HIGH);
pinMode(EN_V, OUTPUT); digitalWrite(EN_V, HIGH);
pinMode(EN_W, OUTPUT); digitalWrite(EN_W, HIGH);
//Setup Interrupt settings
XMC_CCU4_SLICE_COMPARE_CONFIG_t pwm_config = {0};
pwm_config.passive_level = XMC_CCU4_SLICE_OUTPUT_PASSIVE_LEVEL_HIGH;
pwm_config.prescaler_initval = XMC_CCU4_SLICE_PRESCALER_128;
//Setup interrupt1
XMC_CCU4_Init(CCU40, XMC_CCU4_SLICE_MCMS_ACTION_TRANSFER_PR_CR);
XMC_CCU4_SLICE_CompareInit(CCU40_CC43, &pwm_config);
XMC_CCU4_EnableClock(CCU40, 3);
XMC_CCU4_SLICE_SetTimerPeriodMatch(CCU40_CC43, 200); // Adjust last Value or Prescaler
/* Enable compare match and period match events */
XMC_CCU4_SLICE_EnableEvent(CCU40_CC43, XMC_CCU4_SLICE_IRQ_ID_PERIOD_MATCH);
/* Connect period match event to SR0 */
XMC_CCU4_SLICE_SetInterruptNode(CCU40_CC43, XMC_CCU4_SLICE_IRQ_ID_PERIOD_MATCH, XMC_CCU4_SLICE_SR_ID_0);
/* Configure NVIC */
/* Set priority */
NVIC_SetPriority(CCU40_0_IRQn, 10);
/* Enable IRQ */
NVIC_EnableIRQ(CCU40_0_IRQn);
XMC_CCU4_EnableShadowTransfer(CCU40, (CCU4_GCSS_S0SE_Msk << (4 * 3)));
XMC_CCU4_SLICE_StartTimer(CCU40_CC43);
}
void loop() {
// put your main code here, to run repeatedly:
while (Serial.available() != 0)
{
int input = 0;
input = Serial.read();
if(input == 43)
{
duty+=5;
Serial.print("\t\t");
Serial.println(duty);
}
if(input == 45)
{
duty-=5;
Serial.print("\t\t");
Serial.println(duty);
}
}
}
Note: You can use the printed values to set the arrays already and start the motor directly in a controlled way. And "+" and "-" via serial (115200baud) to in/decrease the duty cycle (0-127) in steps of 5.
This mapped phaseshift approach results in a very smooth running motor.
Comments