Skip to content

Commit 3da53b9

Browse files
committed
FEAT added separate driver classes
1 parent fae63ec commit 3da53b9

21 files changed

+427
-185
lines changed

keywords.txt

Lines changed: 6 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -8,6 +8,10 @@ HallSensors KEYWORD1
88
MagneticSensorSPI KEYWORD1
99
MagneticSensorI2C KEYWORD1
1010
MagneticSensorAnalog KEYWORD1
11+
BLDCDriver3PWM KEYWORD1
12+
BLDCDriver KEYWORD1
13+
StepperDriver4PWM KEYWORD1
14+
StepperDriver KEYWORD1
1115

1216
initFOC KEYWORD2
1317
loopFOC KEYWORD2
@@ -36,6 +40,7 @@ Direction KEYWORD1
3640
MagneticSensorI2CConfig_s KEYWORD1
3741
MagneticSensorSPIConfig_s KEYWORD1
3842

43+
linkDriver KEYWORD2
3944
linkSensor KEYWORD2
4045
handleA KEYWORD2
4146
handleB KEYWORD2
@@ -60,11 +65,11 @@ shaft_velocity_sp KEYWORD2
6065
shaft_angle KEYWORD2
6166
shaft_velocity KEYWORD2
6267
controller KEYWORD2
63-
driver KEYWORD2
6468
pullup KEYWORD2
6569
quadrature KEYWORD2
6670
foc_modulation KEYWORD2
6771
target KEYWORD2
72+
pwm_frequency KEYWORD2
6873

6974

7075
voltage KEYWORD2

src/BLDCDriver3PWM.cpp

Lines changed: 69 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,69 @@
1+
#include "BLDCDriver3PWM.h"
2+
3+
BLDCDriver3PWM::BLDCDriver3PWM(int phA, int phB, int phC, int en){
4+
// Pin initialization
5+
pwmA = phA;
6+
pwmB = phB;
7+
pwmC = phC;
8+
9+
// enable_pin pin
10+
enable_pin = en;
11+
12+
// default power-supply value
13+
voltage_power_supply = DEF_POWER_SUPPLY;
14+
voltage_limit = NOT_SET
15+
16+
}
17+
18+
// enable motor driver
19+
void BLDCDriver3PWM::enable(){
20+
// enable_pin the driver - if enable_pin pin available
21+
if ( enable_pin != NOT_SET ) digitalWrite(enable_pin, HIGH);
22+
// set zero to PWM
23+
setPwm(0,0,0);
24+
}
25+
26+
// disable motor driver
27+
void BLDCDriver3PWM::disable()
28+
{
29+
// set zero to PWM
30+
setPwm(0, 0, 0);
31+
// disable the driver - if enable_pin pin available
32+
if ( enable_pin != NOT_SET ) digitalWrite(enable_pin, LOW);
33+
34+
}
35+
36+
// init hardware pins
37+
void BLDCDriver3PWM::init() {
38+
39+
// PWM pins
40+
pinMode(pwmA, OUTPUT);
41+
pinMode(pwmB, OUTPUT);
42+
pinMode(pwmC, OUTPUT);
43+
if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT);
44+
45+
46+
// sanity check for the voltage limit configuration
47+
if(voltage_limit == NOT_SET || voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply;
48+
49+
// Set the pwm frequency to the pins
50+
// hardware specific function - depending on driver and mcu
51+
_setPwmFrequency(pwm_frequency, pwmA, pwmB, pwmC);
52+
}
53+
54+
55+
// Set voltage to the pwm pin
56+
void BLDCDriver3PWM::setPwm(float Ua, float Ub, float Uc) {
57+
// limit the voltage in driver
58+
Ua = _constrain(Ua, -voltage_limit, voltage_limit);
59+
Ub = _constrain(Ub, -voltage_limit, voltage_limit);
60+
Uc = _constrain(Uc, -voltage_limit, voltage_limit);
61+
// calculate duty cycle
62+
// limited in [0,1]
63+
float dc_a = _constrain(Ua / voltage_power_supply, 0 , 1 );
64+
float dc_b = _constrain(Ub / voltage_power_supply, 0 , 1 );
65+
float dc_c = _constrain(Uc / voltage_power_supply, 0 , 1 );
66+
// hardware specific writing
67+
// hardware specific function - depending on driver and mcu
68+
_writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC);
69+
}

src/BLDCDriver3PWM.h

Lines changed: 51 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,51 @@
1+
#ifndef BLDCDriver3PWM_h
2+
#define BLDCDriver3PWM_h
3+
4+
#include "common/interfaces/BLDCDriver.h"
5+
#include "common/foc_utils.h"
6+
#include "common/hardware_utils.h"
7+
#include "common/defaults.h"
8+
9+
/**
10+
3 pwm bldc driver class
11+
*/
12+
class BLDCDriver3PWM: public BLDCDriver
13+
{
14+
public:
15+
/**
16+
BLDCDriver class constructor
17+
@param phA A phase pwm pin
18+
@param phB B phase pwm pin
19+
@param phC C phase pwm pin
20+
@param en enable pin (optional input)
21+
*/
22+
BLDCDriver3PWM(int phA,int phB,int phC, int en = NOT_SET);
23+
24+
/** Motor hardware init function */
25+
void init() override;
26+
/** Motor disable function */
27+
void disable() override;
28+
/** Motor enable function */
29+
void enable() override;
30+
31+
// hardware variables
32+
int pwmA; //!< phase A pwm pin number
33+
int pwmB; //!< phase B pwm pin number
34+
int pwmC; //!< phase C pwm pin number
35+
int enable_pin; //!< enable pin number
36+
37+
/**
38+
* Set phase voltages to the harware
39+
*
40+
* @param Ua - phase A voltage
41+
* @param Ub - phase B voltage
42+
* @param Uc - phase C voltage
43+
*/
44+
void setPwm(float Ua, float Ub, float Uc) override;
45+
46+
private:
47+
48+
};
49+
50+
51+
#endif

src/BLDCMotor.cpp

Lines changed: 38 additions & 53 deletions
Original file line numberDiff line numberDiff line change
@@ -5,37 +5,35 @@
55
// - pp - pole pair number
66
// - cpr - counts per rotation number (cpm=ppm*4)
77
// - enable pin - (optional input)
8-
BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en)
8+
BLDCMotor::BLDCMotor( int phA, int phB, int phC, int pp, int cpr, int en){
9+
10+
}
11+
12+
// BLDCMotor( int pp)
13+
// - phA, phB, phC - motor A,B,C phase pwm pins
14+
// - pp - pole pair number
15+
// - cpr - counts per rotation number (cpm=ppm*4)
16+
// - enable pin - (optional input)
17+
BLDCMotor::BLDCMotor(int pp)
918
: FOCMotor()
1019
{
11-
// Pin initialization
12-
pwmA = phA;
13-
pwmB = phB;
14-
pwmC = phC;
20+
// save pole pairs number
1521
pole_pairs = pp;
22+
}
1623

17-
// enable_pin pin
18-
enable_pin = en;
1924

25+
/**
26+
Link the driver which controls the motor
27+
*/
28+
void BLDCMotor::linkDriver(BLDCDriver* _driver) {
29+
driver = _driver;
2030
}
2131

22-
2332
// init hardware pins
24-
void BLDCMotor::init(long pwm_frequency) {
25-
if(monitor_port) monitor_port->println("MOT: Init pins.");
26-
// PWM pins
27-
pinMode(pwmA, OUTPUT);
28-
pinMode(pwmB, OUTPUT);
29-
pinMode(pwmC, OUTPUT);
30-
if(enable_pin != NOT_SET) pinMode(enable_pin, OUTPUT);
31-
32-
if(monitor_port) monitor_port->println("MOT: PWM config.");
33-
// Increase PWM frequency to 32 kHz
34-
// make silent
35-
_setPwmFrequency(pwm_frequency, pwmA, pwmB, pwmC);
36-
33+
void BLDCMotor::init() {
34+
if(monitor_port) monitor_port->println("MOT: Initialise variables.");
3735
// sanity check for the voltage limit configuration
38-
if(voltage_limit > voltage_power_supply) voltage_limit = voltage_power_supply;
36+
if(voltage_limit > driver->voltage_power_supply) voltage_limit = driver->voltage_power_supply;
3937
// constrain voltage for sensor alignment
4038
if(voltage_sensor_align > voltage_limit) voltage_sensor_align = voltage_limit;
4139
// update the controller limits
@@ -44,7 +42,7 @@ void BLDCMotor::init(long pwm_frequency) {
4442

4543
_delay(500);
4644
// enable motor
47-
if(monitor_port) monitor_port->println("MOT: Enable.");
45+
if(monitor_port) monitor_port->println("MOT: Enable driver.");
4846
enable();
4947
_delay(500);
5048
}
@@ -53,18 +51,18 @@ void BLDCMotor::init(long pwm_frequency) {
5351
// disable motor driver
5452
void BLDCMotor::disable()
5553
{
56-
// disable the driver - if enable_pin pin available
57-
if (enable_pin != NOT_SET) digitalWrite(enable_pin, LOW);
5854
// set zero to PWM
59-
setPwm(0, 0, 0);
55+
driver->setPwm(0, 0, 0);
56+
// disable the driver
57+
driver->disable();
6058
}
6159
// enable motor driver
6260
void BLDCMotor::enable()
6361
{
62+
// enable the driver
63+
driver->enable();
6464
// set zero to PWM
65-
setPwm(0, 0, 0);
66-
// enable_pin the driver - if enable_pin pin available
67-
if (enable_pin != NOT_SET) digitalWrite(enable_pin, HIGH);
65+
driver->setPwm(0, 0, 0);
6866

6967
}
7068

@@ -240,9 +238,9 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) {
240238
Ubeta = _cos(angle_el) * Uq; // cos(angle) * Uq;
241239

242240
// Clarke transform
243-
Ua = Ualpha + voltage_power_supply/2;
244-
Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + voltage_power_supply/2;
245-
Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + voltage_power_supply/2;
241+
Ua = Ualpha + driver->voltage_power_supply/2;
242+
Ub = -0.5 * Ualpha + _SQRT3_2 * Ubeta + driver->voltage_power_supply/2;
243+
Uc = -0.5 * Ualpha - _SQRT3_2 * Ubeta + driver->voltage_power_supply/2;
246244
break;
247245

248246
case FOCModulationType::SpaceVectorPWM :
@@ -261,10 +259,10 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) {
261259
// find the sector we are in currently
262260
int sector = floor(angle_el / _PI_3) + 1;
263261
// calculate the duty cycles
264-
float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/voltage_power_supply;
265-
float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/voltage_power_supply;
262+
float T1 = _SQRT3*_sin(sector*_PI_3 - angle_el) * Uq/driver->voltage_power_supply;
263+
float T2 = _SQRT3*_sin(angle_el - (sector-1.0)*_PI_3) * Uq/driver->voltage_power_supply;
266264
// two versions possible
267-
// centered around voltage_power_supply/2
265+
// centered around driver->voltage_power_supply/2
268266
float T0 = 1 - T1 - T2;
269267
// pulled to 0 - better for low power supply voltage
270268
//float T0 = 0;
@@ -310,27 +308,14 @@ void BLDCMotor::setPhaseVoltage(float Uq, float angle_el) {
310308
}
311309

312310
// calculate the phase voltages and center
313-
Ua = Ta*voltage_power_supply;
314-
Ub = Tb*voltage_power_supply;
315-
Uc = Tc*voltage_power_supply;
311+
Ua = Ta*driver->voltage_power_supply;
312+
Ub = Tb*driver->voltage_power_supply;
313+
Uc = Tc*driver->voltage_power_supply;
316314
break;
317315
}
318316

319-
// set the voltages in hardware
320-
setPwm(Ua, Ub, Uc);
321-
}
322-
323-
324-
325-
// Set voltage to the pwm pin
326-
void BLDCMotor::setPwm(float Ua, float Ub, float Uc) {
327-
// calculate duty cycle
328-
// limited in [0,1]
329-
float dc_a = constrain(Ua / voltage_power_supply, 0 , 1 );
330-
float dc_b = constrain(Ub / voltage_power_supply, 0 , 1 );
331-
float dc_c = constrain(Uc / voltage_power_supply, 0 , 1 );
332-
// hardware specific writing
333-
_writeDutyCycle(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC );
317+
// set the voltages in driver
318+
driver->setPwm(Ua, Ub, Uc);
334319
}
335320

336321

src/BLDCMotor.h

Lines changed: 24 additions & 23 deletions
Original file line numberDiff line numberDiff line change
@@ -9,6 +9,7 @@
99
#include "Arduino.h"
1010
#include "common/interfaces/FOCMotor.h"
1111
#include "common/interfaces/Sensor.h"
12+
#include "common/interfaces/BLDCDriver.h"
1213
#include "common/foc_utils.h"
1314
#include "common/hardware_utils.h"
1415
#include "common/defaults.h"
@@ -20,18 +21,28 @@ class BLDCMotor: public FOCMotor
2021
{
2122
public:
2223
/**
23-
BLDCMotor class constructor
24-
@param phA A phase pwm pin
25-
@param phB B phase pwm pin
26-
@param phC C phase pwm pin
27-
@param pp pole pair number
28-
@param cpr counts per rotation number (cpm=ppm*4)
29-
@param en enable pin (optional input)
24+
BLDCMotor class constructor
25+
@param pp pole pairs number
26+
*/
27+
BLDCMotor(int pp);
28+
29+
30+
/**
31+
* Function linking a motor and a foc driver
32+
*
33+
* @param driver BLDCDriver class implementing all the hardware specific functions necessary PWM setting
34+
*/
35+
void linkDriver(BLDCDriver* driver);
36+
37+
/**
38+
* BLDCDriver link:
39+
* - 3PWM
40+
* - 6PWM
3041
*/
31-
BLDCMotor(int phA,int phB,int phC,int pp, int en = NOT_SET);
42+
BLDCDriver* driver;
3243

3344
/** Motor hardware init function */
34-
void init(long pwm_frequency = NOT_SET) override;
45+
void init() override;
3546
/** Motor disable function */
3647
void disable() override;
3748
/** Motor enable function */
@@ -59,12 +70,9 @@ class BLDCMotor: public FOCMotor
5970
* This function doesn't need to be run upon each loop execution - depends of the use case
6071
*/
6172
void move(float target = NOT_SET) override;
62-
63-
// hardware variables
64-
int pwmA; //!< phase A pwm pin number
65-
int pwmB; //!< phase B pwm pin number
66-
int pwmC; //!< phase C pwm pin number
67-
int enable_pin; //!< enable pin number
73+
74+
float Ua,Ub,Uc;//!< Current phase voltages Ua,Ub and Uc set to motor
75+
float Ualpha,Ubeta; //!< Phase voltages U alpha and U beta used for inverse Park and Clarke transform
6876

6977

7078
private:
@@ -81,14 +89,7 @@ class BLDCMotor: public FOCMotor
8189
int alignSensor();
8290
/** Motor and sensor alignment to the sensors absolute 0 angle */
8391
int absoluteZeroAlign();
84-
/**
85-
* Set phase voltages to the harware
86-
*
87-
* @param Ua phase A voltage
88-
* @param Ub phase B voltage
89-
* @param Uc phase C voltage
90-
*/
91-
void setPwm(float Ua, float Ub, float Uc);
92+
9293

9394
// Open loop motion control
9495
/**

src/SimpleFOC.h

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -93,5 +93,7 @@ void loop() {
9393
#include "MagneticSensorI2C.h"
9494
#include "MagneticSensorAnalog.h"
9595
#include "HallSensor.h"
96+
#include "BLDCDriver3PWM.h"
97+
#include "StepperDriver4PWM.h"
9698

9799
#endif

0 commit comments

Comments
 (0)