Skip to content

Commit 912bfcd

Browse files
committed
driver refactoring (completely unfinished!)
1 parent 34c0399 commit 912bfcd

File tree

12 files changed

+90
-63
lines changed

12 files changed

+90
-63
lines changed

src/common/base_classes/StepperDriver.h

Lines changed: 4 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,6 +1,8 @@
11
#ifndef STEPPERDRIVER_H
22
#define STEPPERDRIVER_H
33

4+
#include "drivers/hardware_api.h"
5+
46
class StepperDriver{
57
public:
68

@@ -16,7 +18,8 @@ class StepperDriver{
1618
float voltage_limit; //!< limiting voltage set to the motor
1719

1820
bool initialized = false; // true if driver was successfully initialized
19-
21+
HardwareDriverParams params = 0;
22+
2023
/**
2124
* Set phase voltages to the harware
2225
*

src/current_sense/hardware_specific/stm32g4_mcu.cpp

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,5 +1,6 @@
11
#include "../hardware_api.h"
22
#include "stm32g4_hal.h"
3+
#include "Arduino.h"
34

45
#if defined(STM32G4xx)
56
#define _ADC_VOLTAGE 3.3
@@ -29,9 +30,10 @@ float _readADCVoltageInline(const int pin){
2930
raw_adc = adcBuffer1[1];
3031
else if(pin == PA6) // = ADC2_IN3 = phase V (OP2_OUT) on B-G431B-ESC1
3132
raw_adc = adcBuffer2[0];
33+
#ifdef PB1
3234
else if(pin == PB1) // = ADC1_IN12 = phase W (OP3_OUT) on B-G431B-ESC1
3335
raw_adc = adcBuffer1[0];
34-
36+
#endif
3537
return raw_adc * _ADC_CONV;
3638
}
3739
// do the same for low side sensing

src/drivers/BLDCDriver3PWM.cpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -56,9 +56,8 @@ int BLDCDriver3PWM::init() {
5656

5757
// Set the pwm frequency to the pins
5858
// hardware specific function - depending on driver and mcu
59-
_configure3PWM(pwm_frequency, pwmA, pwmB, pwmC);
60-
initialized = true; // TODO atm the api gives no feedback if initialization succeeded
61-
return 0;
59+
params = _configure3PWM(pwm_frequency, pwmA, pwmB, pwmC);
60+
return params!=0 && params->initSuccess;
6261
}
6362

6463

@@ -88,5 +87,5 @@ void BLDCDriver3PWM::setPwm(float Ua, float Ub, float Uc) {
8887

8988
// hardware specific writing
9089
// hardware specific function - depending on driver and mcu
91-
_writeDutyCycle3PWM(dc_a, dc_b, dc_c, pwmA, pwmB, pwmC);
90+
_writeDutyCycle3PWM(dc_a, dc_b, dc_c, params);
9291
}

src/drivers/BLDCDriver3PWM.h

Lines changed: 0 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -58,7 +58,6 @@ class BLDCDriver3PWM: public BLDCDriver
5858
*/
5959
virtual void setPhaseState(int sa, int sb, int sc) override;
6060
private:
61-
6261
};
6362

6463

src/drivers/BLDCDriver6PWM.cpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -58,9 +58,8 @@ int BLDCDriver6PWM::init() {
5858

5959
// configure 6pwm
6060
// hardware specific function - depending on driver and mcu
61-
int result = _configure6PWM(pwm_frequency, dead_zone, pwmA_h,pwmA_l, pwmB_h,pwmB_l, pwmC_h,pwmC_l);
62-
initialized = (result==0);
63-
return result;
61+
params = _configure6PWM(pwm_frequency, dead_zone, pwmA_h,pwmA_l, pwmB_h,pwmB_l, pwmC_h,pwmC_l);
62+
return params!=0 && params->initSuccess;
6463
}
6564

6665
// Set voltage to the pwm pin
@@ -76,7 +75,7 @@ void BLDCDriver6PWM::setPwm(float Ua, float Ub, float Uc) {
7675
dc_c = _constrain(Uc / voltage_power_supply, 0.0f , 1.0f );
7776
// hardware specific writing
7877
// hardware specific function - depending on driver and mcu
79-
_writeDutyCycle6PWM(dc_a, dc_b, dc_c, dead_zone, pwmA_h,pwmA_l, pwmB_h,pwmB_l, pwmC_h,pwmC_l);
78+
_writeDutyCycle6PWM(dc_a, dc_b, dc_c, dead_zone, params);
8079
}
8180

8281

src/drivers/StepperDriver2PWM.cpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -79,9 +79,8 @@ int StepperDriver2PWM::init() {
7979

8080
// Set the pwm frequency to the pins
8181
// hardware specific function - depending on driver and mcu
82-
_configure2PWM(pwm_frequency, pwm1, pwm2);
83-
initialized = true; // TODO atm the api gives no feedback if initialization succeeded
84-
return 0;
82+
params = _configure2PWM(pwm_frequency, pwm1, pwm2);
83+
return params!=0 && params->initSuccess;
8584
}
8685

8786

@@ -103,5 +102,5 @@ void StepperDriver2PWM::setPwm(float Ua, float Ub) {
103102
if( _isset(dir2b) ) digitalWrite(dir2b, Ub >= 0 ? HIGH : LOW );
104103

105104
// write to hardware
106-
_writeDutyCycle2PWM(duty_cycle1, duty_cycle2, pwm1, pwm2);
105+
_writeDutyCycle2PWM(duty_cycle1, duty_cycle2, params);
107106
}

src/drivers/StepperDriver4PWM.cpp

Lines changed: 3 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -54,9 +54,8 @@ int StepperDriver4PWM::init() {
5454

5555
// Set the pwm frequency to the pins
5656
// hardware specific function - depending on driver and mcu
57-
_configure4PWM(pwm_frequency, pwm1A, pwm1B, pwm2A, pwm2B);
58-
initialized = true; // TODO atm the api gives no feedback if initialization succeeded
59-
return 0;
57+
params = _configure4PWM(pwm_frequency, pwm1A, pwm1B, pwm2A, pwm2B);
58+
return params!=0 && params->initSuccess;
6059
}
6160

6261

@@ -77,5 +76,5 @@ void StepperDriver4PWM::setPwm(float Ualpha, float Ubeta) {
7776
else
7877
duty_cycle2A = _constrain(abs(Ubeta)/voltage_power_supply,0.0f,1.0f);
7978
// write to hardware
80-
_writeDutyCycle4PWM(duty_cycle1A, duty_cycle1B, duty_cycle2A, duty_cycle2B, pwm1A, pwm1B, pwm2A, pwm2B);
79+
_writeDutyCycle4PWM(duty_cycle1A, duty_cycle1B, duty_cycle2A, duty_cycle2B, params);
8180
}

src/drivers/hardware_api.h

Lines changed: 20 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -4,6 +4,18 @@
44
#include "../common/foc_utils.h"
55
#include "../common/time_utils.h"
66

7+
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+
17+
18+
719
/**
820
* Configuring PWM frequency, resolution and alignment
921
* - Stepper driver - 2PWM setting
@@ -13,7 +25,7 @@
1325
* @param pinA pinA bldc driver
1426
* @param pinB pinB bldc driver
1527
*/
16-
void _configure2PWM(long pwm_frequency, const int pinA, const int pinB);
28+
HardwareDriverParams _configure2PWM(long pwm_frequency, const int pinA, const int pinB);
1729

1830
/**
1931
* Configuring PWM frequency, resolution and alignment
@@ -25,7 +37,7 @@ void _configure2PWM(long pwm_frequency, const int pinA, const int pinB);
2537
* @param pinB pinB bldc driver
2638
* @param pinC pinC bldc driver
2739
*/
28-
void _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC);
40+
HardwareDriverParams _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC);
2941

3042
/**
3143
* Configuring PWM frequency, resolution and alignment
@@ -38,7 +50,7 @@ void _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const in
3850
* @param pin2A pin2A stepper driver
3951
* @param pin2B pin2B stepper driver
4052
*/
41-
void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B);
53+
HardwareDriverParams _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B);
4254

4355
/**
4456
* Configuring PWM frequency, resolution and alignment
@@ -56,7 +68,7 @@ void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const
5668
*
5769
* @return 0 if config good, -1 if failed
5870
*/
59-
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);
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);
6072

6173
/**
6274
* Function setting the duty cycle to the pwm pin (ex. analogWrite())
@@ -68,7 +80,7 @@ int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const
6880
* @param pinA phase A hardware pin number
6981
* @param pinB phase B hardware pin number
7082
*/
71-
void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB);
83+
void _writeDutyCycle2PWM(float dc_a, float dc_b, HardwareDriverParams params = 0);
7284

7385
/**
7486
* Function setting the duty cycle to the pwm pin (ex. analogWrite())
@@ -82,7 +94,7 @@ void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB);
8294
* @param pinB phase B hardware pin number
8395
* @param pinC phase C hardware pin number
8496
*/
85-
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC);
97+
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, HardwareDriverParams params = 0);
8698

8799
/**
88100
* Function setting the duty cycle to the pwm pin (ex. analogWrite())
@@ -98,7 +110,7 @@ void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB
98110
* @param pin2A phase 2A hardware pin number
99111
* @param pin2B phase 2B hardware pin number
100112
*/
101-
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B);
113+
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, HardwareDriverParams params = 0);
102114

103115

104116
/**
@@ -118,6 +130,6 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, in
118130
* @param pinC_l phase C low-side hardware pin number
119131
*
120132
*/
121-
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);
133+
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, HardwareDriverParams params = 0);
122134

123135
#endif

src/drivers/hardware_specific/generic_mcu.cpp

Lines changed: 29 additions & 28 deletions
Original file line numberDiff line numberDiff line change
@@ -9,52 +9,53 @@
99
// - Stepper motor - 2PWM setting
1010
// - hardware speciffic
1111
// in generic case dont do anything
12-
__attribute__((weak)) void _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
13-
_UNUSED(pwm_frequency);
14-
_UNUSED(pinA);
15-
_UNUSED(pinB);
16-
return;
12+
__attribute__((weak)) HardwareDriverParams _configure2PWM(long pwm_frequency,const int pinA, const int pinB) {
13+
HardwareDriverParams params = new struct DriverParamsBase {
14+
.pins = { pinA, pinB, -1, -1, -1, -1 },
15+
.pwm_frequency = pwm_frequency,
16+
.initSuccess = true
17+
};
18+
return params;
1719
}
1820

1921
// function setting the high pwm frequency to the supplied pins
2022
// - BLDC motor - 3PWM setting
2123
// - hardware speciffic
2224
// in generic case dont do anything
23-
__attribute__((weak)) void _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
24-
_UNUSED(pwm_frequency);
25-
_UNUSED(pinA);
26-
_UNUSED(pinB);
27-
_UNUSED(pinC);
28-
return;
25+
__attribute__((weak)) HardwareDriverParams _configure3PWM(long pwm_frequency,const int pinA, const int pinB, const int pinC) {
26+
HardwareDriverParams params = new struct DriverParamsBase {
27+
.pins = { pinA, pinB, pinC, -1, -1, -1 },
28+
.pwm_frequency = pwm_frequency,
29+
.initSuccess = true
30+
};
31+
return params;
2932
}
3033

3134

3235
// function setting the high pwm frequency to the supplied pins
3336
// - Stepper motor - 4PWM setting
3437
// - hardware speciffic
3538
// in generic case dont do anything
36-
__attribute__((weak)) void _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
37-
_UNUSED(pwm_frequency);
38-
_UNUSED(pin1A);
39-
_UNUSED(pin1B);
40-
_UNUSED(pin2A);
41-
_UNUSED(pin2B);
42-
return;
39+
__attribute__((weak)) HardwareDriverParams _configure4PWM(long pwm_frequency,const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
40+
HardwareDriverParams params = new struct DriverParamsBase {
41+
.pins = { pin1A, pin1B, pin2A, pin2B, -1, -1 },
42+
.pwm_frequency = pwm_frequency,
43+
.initSuccess = true
44+
};
45+
return params;
4346
}
4447

4548
// Configuring PWM frequency, resolution and alignment
4649
// - BLDC driver - 6PWM setting
4750
// - hardware specific
48-
__attribute__((weak)) 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){
49-
_UNUSED(pwm_frequency);
50-
_UNUSED(dead_zone);
51-
_UNUSED(pinA_h);
52-
_UNUSED(pinB_h);
53-
_UNUSED(pinC_h);
54-
_UNUSED(pinA_l);
55-
_UNUSED(pinB_l);
56-
_UNUSED(pinC_l);
57-
return -1;
51+
__attribute__((weak)) 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){
52+
HardwareDriverParams params = new struct DriverParamsBase {
53+
.pins = { pinA_h, pinA_l, pinB_h, pinB_l, pinC_h, pinC_l },
54+
.pwm_frequency = pwm_frequency,
55+
.dead_zone = dead_zone,
56+
.initSuccess = true
57+
};
58+
return params;
5859
}
5960

6061

src/drivers/hardware_specific/samd_mcu.cpp

Lines changed: 8 additions & 8 deletions
Original file line numberDiff line numberDiff line change
@@ -278,7 +278,7 @@ int checkPermutations(uint8_t num, int pins[], bool (*checkFunc)(tccConfiguratio
278278
* @param pinA pinA bldc driver
279279
* @param pinB pinB bldc driver
280280
*/
281-
void _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
281+
HardwareDriverParams _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
282282
#ifdef SIMPLEFOC_SAMD_DEBUG
283283
printAllPinInfos();
284284
#endif
@@ -375,7 +375,7 @@ void _configure2PWM(long pwm_frequency, const int pinA, const int pinB) {
375375
* @param pinB pinB bldc driver
376376
* @param pinC pinC bldc driver
377377
*/
378-
void _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC) {
378+
HardwareDriverParams _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const int pinC) {
379379
#ifdef SIMPLEFOC_SAMD_DEBUG
380380
printAllPinInfos();
381381
#endif
@@ -451,7 +451,7 @@ void _configure3PWM(long pwm_frequency, const int pinA, const int pinB, const in
451451
* @param pin2A pin2A stepper driver
452452
* @param pin2B pin2B stepper driver
453453
*/
454-
void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
454+
HardwareDriverParams _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const int pin2A, const int pin2B) {
455455
#ifdef SIMPLEFOC_SAMD_DEBUG
456456
printAllPinInfos();
457457
#endif
@@ -552,7 +552,7 @@ void _configure4PWM(long pwm_frequency, const int pin1A, const int pin1B, const
552552
*
553553
* @return 0 if config good, -1 if failed
554554
*/
555-
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) {
555+
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) {
556556
// we want to use a TCC channel with 1 non-inverted and 1 inverted output for each phase, with dead-time insertion
557557
#ifdef SIMPLEFOC_SAMD_DEBUG
558558
printAllPinInfos();
@@ -644,7 +644,7 @@ int _configure6PWM(long pwm_frequency, float dead_zone, const int pinA_h, const
644644
* @param pinA phase A hardware pin number
645645
* @param pinB phase B hardware pin number
646646
*/
647-
void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB) {
647+
void _writeDutyCycle2PWM(float dc_a, float dc_b, HardwareDriverParams params) {
648648
tccConfiguration* tccI = getTccPinConfiguration(pinA);
649649
writeSAMDDutyCycle(tccI, dc_a);
650650
tccI = getTccPinConfiguration(pinB);
@@ -668,7 +668,7 @@ void _writeDutyCycle2PWM(float dc_a, float dc_b, int pinA, int pinB) {
668668
* @param pinB phase B hardware pin number
669669
* @param pinC phase C hardware pin number
670670
*/
671-
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB, int pinC) {
671+
void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, HardwareDriverParams params) {
672672
tccConfiguration* tccI = getTccPinConfiguration(pinA);
673673
writeSAMDDutyCycle(tccI, dc_a);
674674
tccI = getTccPinConfiguration(pinB);
@@ -695,7 +695,7 @@ void _writeDutyCycle3PWM(float dc_a, float dc_b, float dc_c, int pinA, int pinB
695695
* @param pin2A phase 2A hardware pin number
696696
* @param pin2B phase 2B hardware pin number
697697
*/
698-
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, int pin1A, int pin1B, int pin2A, int pin2B){
698+
void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, HardwareDriverParams params){
699699
tccConfiguration* tccI = getTccPinConfiguration(pin1A);
700700
writeSAMDDutyCycle(tccI, dc_1a);
701701
tccI = getTccPinConfiguration(pin2A);
@@ -733,7 +733,7 @@ void _writeDutyCycle4PWM(float dc_1a, float dc_1b, float dc_2a, float dc_2b, in
733733
* @param pinC_l phase C low-side hardware pin number
734734
*
735735
*/
736-
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){
736+
void _writeDutyCycle6PWM(float dc_a, float dc_b, float dc_c, float dead_zone, HardwareDriverParams params){
737737
tccConfiguration* tcc1 = getTccPinConfiguration(pinA_h);
738738
tccConfiguration* tcc2 = getTccPinConfiguration(pinA_l);
739739
if (tcc1->tcc.chaninfo!=tcc2->tcc.chaninfo) {

0 commit comments

Comments
 (0)