Skip to content

Commit 7f02b8a

Browse files
committed
driver API refactor, part 1, the easy ones
1 parent 912bfcd commit 7f02b8a

16 files changed

+371
-276
lines changed

src/common/base_classes/BLDCDriver.h

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -23,6 +23,7 @@ class BLDCDriver{
2323
float dc_c; //!< currently set duty cycle on phaseC
2424

2525
bool initialized = false; // true if driver was successfully initialized
26+
void* params = 0; // pointer to hardware specific parameters of driver
2627

2728
/**
2829
* Set phase voltages to the harware

src/common/base_classes/StepperDriver.h

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -18,7 +18,7 @@ class StepperDriver{
1818
float voltage_limit; //!< limiting voltage set to the motor
1919

2020
bool initialized = false; // true if driver was successfully initialized
21-
HardwareDriverParams params = 0;
21+
void* params = 0; // pointer to hardware specific parameters of driver
2222

2323
/**
2424
* Set phase voltages to the harware

src/drivers/BLDCDriver3PWM.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -57,7 +57,7 @@ int BLDCDriver3PWM::init() {
5757
// Set the pwm frequency to the pins
5858
// hardware specific function - depending on driver and mcu
5959
params = _configure3PWM(pwm_frequency, pwmA, pwmB, pwmC);
60-
return params!=0 && params->initSuccess;
60+
return params!=SIMPLEFOC_DRIVER_INIT_FAILED;
6161
}
6262

6363

src/drivers/BLDCDriver6PWM.cpp

Lines changed: 3 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -59,9 +59,10 @@ int BLDCDriver6PWM::init() {
5959
// configure 6pwm
6060
// hardware specific function - depending on driver and mcu
6161
params = _configure6PWM(pwm_frequency, dead_zone, pwmA_h,pwmA_l, pwmB_h,pwmB_l, pwmC_h,pwmC_l);
62-
return params!=0 && params->initSuccess;
62+
return params!=SIMPLEFOC_DRIVER_INIT_FAILED;
6363
}
6464

65+
6566
// Set voltage to the pwm pin
6667
void BLDCDriver6PWM::setPwm(float Ua, float Ub, float Uc) {
6768
// limit the voltage in driver
@@ -75,7 +76,7 @@ void BLDCDriver6PWM::setPwm(float Ua, float Ub, float Uc) {
7576
dc_c = _constrain(Uc / voltage_power_supply, 0.0f , 1.0f );
7677
// hardware specific writing
7778
// hardware specific function - depending on driver and mcu
78-
_writeDutyCycle6PWM(dc_a, dc_b, dc_c, dead_zone, params);
79+
_writeDutyCycle6PWM(dc_a, dc_b, dc_c, params);
7980
}
8081

8182

src/drivers/StepperDriver2PWM.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -80,7 +80,7 @@ int StepperDriver2PWM::init() {
8080
// Set the pwm frequency to the pins
8181
// hardware specific function - depending on driver and mcu
8282
params = _configure2PWM(pwm_frequency, pwm1, pwm2);
83-
return params!=0 && params->initSuccess;
83+
return params!=SIMPLEFOC_DRIVER_INIT_FAILED;
8484
}
8585

8686

src/drivers/StepperDriver4PWM.cpp

Lines changed: 1 addition & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -55,7 +55,7 @@ int StepperDriver4PWM::init() {
5555
// Set the pwm frequency to the pins
5656
// hardware specific function - depending on driver and mcu
5757
params = _configure4PWM(pwm_frequency, pwm1A, pwm1B, pwm2A, pwm2B);
58-
return params!=0 && params->initSuccess;
58+
return params!=SIMPLEFOC_DRIVER_INIT_FAILED;
5959
}
6060

6161

src/drivers/hardware_api.h

Lines changed: 25 additions & 34 deletions
Original file line numberDiff line numberDiff line change
@@ -4,16 +4,13 @@
44
#include "../common/foc_utils.h"
55
#include "../common/time_utils.h"
66

7+
#define SIMPLEFOC_DRIVER_INIT_FAILED ((void*)-1)
78

8-
struct HardwareDriverParamsBase {
9-
int pins[6];
10-
long pwm_frequency;
11-
int dead_zone;
12-
bool initSuccess;
13-
};
14-
15-
typedef struct HardwareDriverParamsBase* HardwareDriverParams;
16-
9+
typedef struct GenericDriverParams {
10+
int pins[6];
11+
long pwm_frequency;
12+
float dead_zone;
13+
} GenericDriverParams;
1714

1815

1916
/**
@@ -24,8 +21,10 @@ typedef struct HardwareDriverParamsBase* HardwareDriverParams;
2421
* @param pwm_frequency - frequency in hertz - if applicable
2522
* @param pinA pinA bldc driver
2623
* @param pinB pinB bldc driver
24+
*
25+
* @return -1 if failed, or pointer to internal driver parameters struct if successful
2726
*/
28-
HardwareDriverParams _configure2PWM(long pwm_frequency, const int pinA, const int pinB);
27+
void* _configure2PWM(long pwm_frequency, const int pinA, const int pinB);
2928

3029
/**
3130
* Configuring PWM frequency, resolution and alignment
@@ -36,8 +35,10 @@ HardwareDriverParams _configure2PWM(long pwm_frequency, const int pinA, const in
3635
* @param pinA pinA bldc driver
3736
* @param pinB pinB bldc driver
3837
* @param pinC pinC bldc driver
38+
*
39+
* @return -1 if failed, or pointer to internal driver parameters struct if successful
3940
*/
40-
HardwareDriverParams _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC);
41+
void* _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC);
4142

4243
/**
4344
* Configuring PWM frequency, resolution and alignment
@@ -49,8 +50,10 @@ HardwareDriverParams _configure3PWM(long pwm_frequency, const int pinA, const in
4950
* @param pin1B pin1B stepper driver
5051
* @param pin2A pin2A stepper driver
5152
* @param pin2B pin2B stepper driver
53+
*
54+
* @return -1 if failed, or pointer to internal driver parameters struct if successful
5255
*/
53-
HardwareDriverParams _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B);
56+
void* _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B);
5457

5558
/**
5659
* Configuring PWM frequency, resolution and alignment
@@ -66,9 +69,9 @@ HardwareDriverParams _configure4PWM(long pwm_frequency, const int pin1A, const i
6669
* @param pinC_h pinA high-side bldc driver
6770
* @param pinC_l pinA low-side bldc driver
6871
*
69-
* @return 0 if config good, -1 if failed
72+
* @return -1 if failed, or pointer to internal driver parameters struct if successful
7073
*/
71-
HardwareDriverParams _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l);
74+
void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l);
7275

7376
/**
7477
* Function setting the duty cycle to the pwm pin (ex. analogWrite())
@@ -77,10 +80,9 @@ HardwareDriverParams _configure6PWM(long pwm_frequency, float dead_zone, const i
7780
*
7881
* @param dc_a duty cycle phase A [0, 1]
7982
* @param dc_b duty cycle phase B [0, 1]
80-
* @param pinA phase A hardware pin number
81-
* @param pinB phase B hardware pin number
83+
* @param params the driver parameters
8284
*/
83-
void _writeDutyCycle2PWM(float dc_a, float dc_b, HardwareDriverParams params = 0);
85+
void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params);
8486

8587
/**
8688
* Function setting the duty cycle to the pwm pin (ex. analogWrite())
@@ -90,11 +92,9 @@ void _writeDutyCycle2PWM(float dc_a, float dc_b, HardwareDriverParams params =
9092
* @param dc_a duty cycle phase A [0, 1]
9193
* @param dc_b duty cycle phase B [0, 1]
9294
* @param dc_c duty cycle phase C [0, 1]
93-
* @param pinA phase A hardware pin number
94-
* @param pinB phase B hardware pin number
95-
* @param pinC phase C hardware pin number
95+
* @param params the driver parameters
9696
*/
97-
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, HardwareDriverParams params = 0);
97+
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params);
9898

9999
/**
100100
* Function setting the duty cycle to the pwm pin (ex. analogWrite())
@@ -105,12 +105,9 @@ void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, HardwareDriverPara
105105
* @param dc_1b duty cycle phase 1B [0, 1]
106106
* @param dc_2a duty cycle phase 2A [0, 1]
107107
* @param dc_2b duty cycle phase 2B [0, 1]
108-
* @param pin1A phase 1A hardware pin number
109-
* @param pin1B phase 1B hardware pin number
110-
* @param pin2A phase 2A hardware pin number
111-
* @param pin2B phase 2B hardware pin number
108+
* @param params the driver parameters
112109
*/
113-
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, HardwareDriverParams params = 0);
110+
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params);
114111

115112

116113
/**
@@ -121,15 +118,9 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, Ha
121118
* @param dc_a duty cycle phase A [0, 1]
122119
* @param dc_b duty cycle phase B [0, 1]
123120
* @param dc_c duty cycle phase C [0, 1]
124-
* @param dead_zone duty cycle protection zone [0, 1] - both low and high side low
125-
* @param pinA_h phase A high-side hardware pin number
126-
* @param pinA_l phase A low-side hardware pin number
127-
* @param pinB_h phase B high-side hardware pin number
128-
* @param pinB_l phase B low-side hardware pin number
129-
* @param pinC_h phase C high-side hardware pin number
130-
* @param pinC_l phase C low-side hardware pin number
121+
* @param params the driver parameters
131122
*
132123
*/
133-
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, HardwareDriverParams params = 0);
124+
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, void* params);
134125

135126
#endif

src/drivers/hardware_specific/atmega2560_mcu.cpp

Lines changed: 42 additions & 21 deletions
Original file line numberDiff line numberDiff line change
@@ -28,64 +28,79 @@ void _pinHighFrequency(const int pin){
2828
// function setting the high pwm frequency to the supplied pins
2929
// - Stepper motor - 2PWM setting
3030
// - hardware speciffic
31-
void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
31+
void* _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
3232
// High PWM frequency
3333
// - always max 32kHz
3434
_pinHighFrequency(pinA);
3535
_pinHighFrequency(pinB);
36+
GenericDriverParams* params = new GenericDriverParams {
37+
.pins = { pinA, pinB },
38+
.pwm_frequency = pwm_frequency
39+
};
40+
return params;
3641
}
3742

3843
// function setting the high pwm frequency to the supplied pins
3944
// - BLDC motor - 3PWM setting
4045
// - hardware speciffic
41-
void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
46+
void* _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
4247
// High PWM frequency
4348
// - always max 32kHz
4449
_pinHighFrequency(pinA);
4550
_pinHighFrequency(pinB);
4651
_pinHighFrequency(pinC);
52+
GenericDriverParams* params = new GenericDriverParams {
53+
.pins = { pinA, pinB, pinC },
54+
.pwm_frequency = pwm_frequency
55+
};
56+
return params;
4757
}
4858

4959
// function setting the pwm duty cycle to the hardware
5060
// - Stepper motor - 2PWM setting
5161
// - hardware speciffic
52-
void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB){
62+
void _writeDutyCycle2PWM(float dc_a, float dc_b, void* params){
5363
// transform duty cycle from [0,1] to [0,255]
54-
analogWrite(pinA, 255.0f*dc_a);
55-
analogWrite(pinB, 255.0f*dc_b);
64+
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
65+
analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_b);
5666
}
5767

5868
// function setting the pwm duty cycle to the hardware
5969
// - BLDC motor - 3PWM setting
6070
// - hardware speciffic
61-
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC){
71+
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, void* params){
6272
// transform duty cycle from [0,1] to [0,255]
63-
analogWrite(pinA, 255.0f*dc_a);
64-
analogWrite(pinB, 255.0f*dc_b);
65-
analogWrite(pinC, 255.0f*dc_c);
73+
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_a);
74+
analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_b);
75+
analogWrite(((GenericDriverParams*)params)->pins[2], 255.0f*dc_c);
6676
}
6777

6878
// function setting the high pwm frequency to the supplied pins
6979
// - Stepper motor - 4PWM setting
7080
// - hardware speciffic
71-
void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
81+
void* _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
7282
// High PWM frequency
7383
// - always max 32kHz
7484
_pinHighFrequency(pin1A);
7585
_pinHighFrequency(pin1B);
7686
_pinHighFrequency(pin2A);
7787
_pinHighFrequency(pin2B);
88+
GenericDriverParams* params = new GenericDriverParams {
89+
.pins = { pin1A, pin2A, pin2A, pin2B },
90+
.pwm_frequency = pwm_frequency
91+
};
92+
return params;
7893
}
7994

8095
// function setting the pwm duty cycle to the hardware
8196
// - Stepper motor - 4PWM setting
8297
// - hardware speciffic
83-
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){
98+
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, void* params) {
8499
// transform duty cycle from [0,1] to [0,255]
85-
analogWrite(pin1A, 255.0f*dc_1a);
86-
analogWrite(pin1B, 255.0f*dc_1b);
87-
analogWrite(pin2A, 255.0f*dc_2a);
88-
analogWrite(pin2B, 255.0f*dc_2b);
100+
analogWrite(((GenericDriverParams*)params)->pins[0], 255.0f*dc_1a);
101+
analogWrite(((GenericDriverParams*)params)->pins[1], 255.0f*dc_1b);
102+
analogWrite(((GenericDriverParams*)params)->pins[2], 255.0f*dc_2a);
103+
analogWrite(((GenericDriverParams*)params)->pins[3], 255.0f*dc_2b);
89104
}
90105

91106

@@ -122,14 +137,20 @@ int _configureComplementaryPair(int pinH, int pinL) {
122137
// - BLDC driver - 6PWM setting
123138
// - hardware specific
124139
// supports Arudino/ATmega328
125-
int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l) {
140+
void* _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const int pinA_l, const int pinB_h, const int pinB_l, const int pinC_h, const int pinC_l) {
126141
// High PWM frequency
127142
// - always max 32kHz
128143
int ret_flag = 0;
129144
ret_flag += _configureComplementaryPair(pinA_h, pinA_l);
130145
ret_flag += _configureComplementaryPair(pinB_h, pinB_l);
131146
ret_flag += _configureComplementaryPair(pinC_h, pinC_l);
132-
return ret_flag; // returns -1 if not well configured
147+
if (ret_flag!=0) return SIMPLEFOC_DRIVER_INIT_FAILED;
148+
GenericDriverParams* params = new GenericDriverParams {
149+
.pins = { pinA_h,, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l },
150+
.pwm_frequency = pwm_frequency
151+
.dead_zone = dead_zone
152+
};
153+
return params;
133154
}
134155

135156
// function setting the
@@ -149,10 +170,10 @@ void _setPwmPair(int pinH, int pinL, float val, int dead_time)
149170
// - BLDC driver - 6PWM setting
150171
// - hardware specific
151172
// supports Arudino/ATmega328
152-
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, int pinA_h, int pinA_l, int pinB_h, int pinB_l, int pinC_h, int pinC_l){
153-
_setPwmPair(pinA_h, pinA_l, dc_a*255.0, dead_zone*255.0);
154-
_setPwmPair(pinB_h, pinB_l, dc_b*255.0, dead_zone*255.0);
155-
_setPwmPair(pinC_h, pinC_l, dc_c*255.0, dead_zone*255.0);
173+
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, void* params){
174+
_setPwmPair(((GenericDriverParams*)params)->pins[0], ((GenericDriverParams*)params)->pins[1], dc_a*255.0, ((GenericDriverParams*)params)->dead_zone*255.0);
175+
_setPwmPair(((GenericDriverParams*)params)->pins[2], ((GenericDriverParams*)params)->pins[3], dc_b*255.0, ((GenericDriverParams*)params)->dead_zone*255.0);
176+
_setPwmPair(((GenericDriverParams*)params)->pins[4], ((GenericDriverParams*)params)->pins[5], dc_c*255.0, ((GenericDriverParams*)params)->dead_zone*255.0);
156177
}
157178

158179
#endif

0 commit comments

Comments
 (0)