Skip to content

Commit 8d73cd6

Browse files
committed
refactoring
1 parent a3482df commit 8d73cd6

File tree

9 files changed

+52
-87
lines changed

9 files changed

+52
-87
lines changed

BLDCMotor.cpp

Lines changed: 7 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -42,6 +42,9 @@ BLDCMotor::BLDCMotor(int phA, int phB, int phC, int pp, int en)
4242
P_angle.K = DEF_P_ANGLE_K;
4343
// maximum angular velocity to be used for positioning
4444
P_angle.velocity_limit = DEF_P_ANGLE_VEL_LIM;
45+
46+
// driver deafault type
47+
driver = DriverType::bipolar;
4548
}
4649

4750
// init hardware pins
@@ -59,9 +62,11 @@ void BLDCMotor::init() {
5962
setPwmFrequency(pwmB);
6063
setPwmFrequency(pwmC);
6164

62-
driver = DriverType::bipolar;
63-
6465
delay(500);
66+
// enable motor
67+
enable();
68+
delay(500);
69+
6570
}
6671

6772
/*

Encoder.cpp

Lines changed: 8 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -103,7 +103,7 @@ void Encoder::setCounterZero(){
103103
}
104104

105105

106-
void Encoder::init(){
106+
void Encoder::init(void (*doA)(), void(*doB)()){
107107

108108
// Encoder - check if pullup needed for your encoder
109109
if(pullup == INTERN){
@@ -125,17 +125,11 @@ void Encoder::init(){
125125
prev_pulse_counter = 0;
126126
prev_timestamp_us = micros();
127127

128-
129-
}
130-
131128

132-
void Encoder::enableInterrupt(){
133-
// interupt intitialisation
134-
// A callback and B callback
135-
attachInterrupt(digitalPinToInterrupt(pinA), []() {
136-
encoder.handleA();
137-
}, CHANGE);
138-
attachInterrupt(digitalPinToInterrupt(pinB), []() {
139-
encoder.handleB();
140-
}, CHANGE);
141-
}
129+
// attach interrupt if functions provided
130+
if(doA != nullptr){
131+
// A callback and B callback
132+
attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE);
133+
attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE);
134+
}
135+
}

Encoder.h

Lines changed: 4 additions & 4 deletions
Original file line numberDiff line numberDiff line change
@@ -20,17 +20,16 @@ class Encoder{
2020
*/
2121
Encoder(int encA, int encB , float cpr, int index = 0);
2222

23-
// encoder intiialise pins
24-
void init();
23+
// encoder initialise pins
24+
void init(void (*doA)() = nullptr, void(*doB)() = nullptr);
2525

2626
// Encoder interrupt callback functions
2727
// enabling CPR=4xPPR behaviour
2828
// A channel
2929
void handleA();
3030
// B channel
3131
void handleB();
32-
void enableInterrupt();
33-
32+
3433
// encoder getters
3534
// shaft velocity getter
3635
float getVelocity();
@@ -46,6 +45,7 @@ class Encoder{
4645
// encoder pullup type
4746
Pullup pullup;
4847

48+
4949
private:
5050
long pulse_counter; // current pulse counter
5151
long pulse_timestamp; // last impulse timestamp in us

examples/HMBGC_example/HMBGC_example.ino

Lines changed: 7 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -13,30 +13,26 @@ BLDCMotor motor = BLDCMotor(9, 10, 11, 11);
1313
// - cpr - counts per rotation (cpm=ppm*4)
1414
// - index pin - (optional input)
1515
Encoder encoder = Encoder(A1, A0, 2400);
16-
16+
// interrupt ruotine intialisation
17+
void doA(){encoder.handleA();}
18+
void doB(){encoder.handleB();}
1719

1820
// encoder interrupt init
19-
PciListenerImp listenerA(encoder.pinA, []() {
20-
encoder.handleA();
21-
});
22-
PciListenerImp listenerB(encoder.pinB, []() {
23-
encoder.handleB();
24-
});
21+
PciListenerImp listenerA(encoder.pinA, doA);
22+
PciListenerImp listenerB(encoder.pinB, doB);
2523

2624
void setup() {
2725
// debugging port
2826
Serial.begin(115200);
2927

30-
3128
// check if you need internal pullups
3229
// Pullup::EXTERN - external pullup added
3330
// Pullup::INTERN - needs internal arduino pullup
34-
encoder.pullup = Pullup::EXTERN;
31+
encoder.pullup = Pullup::INTERN;
3532
// initialise encoder hardware
3633
encoder.init();
3734

38-
39-
// interupt intitialisation
35+
// interrupt intitialisation
4036
PciManager.registerListener(&listenerA);
4137
PciManager.registerListener(&listenerB);
4238

@@ -66,7 +62,6 @@ void setup() {
6662

6763
// intialise motor
6864
motor.init();
69-
motor.enable();
7065
// align encoder and start FOC
7166
motor.initFOC();
7267

examples/angle_control/angle_control.ino

Lines changed: 5 additions & 5 deletions
Original file line numberDiff line numberDiff line change
@@ -14,20 +14,21 @@ BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8);
1414
// - cpr - counts per rotation (cpm=ppm*4)
1515
// - index pin - (optional input)
1616
Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 32768, 4);
17+
// interrupt ruotine intialisation
18+
void doA(){encoder.handleA();}
19+
void doB(){encoder.handleB();}
1720

1821
void setup() {
1922
// debugging port
2023
Serial.begin(115200);
2124

22-
2325
// check if you need internal pullups
2426
// Pullup::EXTERN - external pullup added
2527
// Pullup::INTERN - needs internal arduino pullup
2628
encoder.pullup = Pullup::EXTERN;
29+
2730
// initialise encoder hardware
28-
encoder.init();
29-
30-
encoder.enableInterrupt();
31+
encoder.init(doA, doB);
3132

3233
// set driver type
3334
// DriverType::unipolar
@@ -61,7 +62,6 @@ void setup() {
6162

6263
// intialise motor
6364
motor.init();
64-
motor.enable();
6565
// align encoder and start FOC
6666
motor.initFOC();
6767

examples/angle_control_serial/angle_control_serial.ino

Lines changed: 5 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -17,28 +17,21 @@ BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8);
1717
// - cpr - counts per rotation (cpm=ppm*4)
1818
// - index pin - (optional input)
1919
Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 32768, 4);
20+
// interrupt ruotine intialisation
21+
void doA(){encoder.handleA();}
22+
void doB(){encoder.handleB();}
2023

2124
void setup() {
2225
// debugging port
2326
Serial.begin(115200);
2427

25-
2628
// check if you need internal pullups
2729
// Pullup::EXTERN - external pullup added
2830
// Pullup::INTERN - needs internal arduino pullup
2931
encoder.pullup = Pullup::EXTERN;
32+
3033
// initialise encoder hardware
31-
encoder.init();
32-
33-
// interupt intitialisation
34-
// A callback and B callback
35-
attachInterrupt(digitalPinToInterrupt(encoder.pinA), []() {
36-
encoder.handleA();
37-
}, CHANGE);
38-
attachInterrupt(digitalPinToInterrupt(encoder.pinB), []() {
39-
encoder.handleB();
40-
}, CHANGE);
41-
34+
encoder.init(doA, doB);
4235
// set driver type
4336
// DriverType::unipolar
4437
// DriverType::bipolar - default
@@ -71,7 +64,6 @@ void setup() {
7164

7265
// intialise motor
7366
motor.init();
74-
motor.enable();
7567
// align encoder and start FOC
7668
motor.initFOC();
7769

examples/velocity_control/velocity_control.ino

Lines changed: 6 additions & 13 deletions
Original file line numberDiff line numberDiff line change
@@ -14,27 +14,21 @@ BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8);
1414
// - cpr - counts per rotation (cpm=ppm*4)
1515
// - index pin - (optional input)
1616
Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 32768, 4);
17+
// interrupt ruotine intialisation
18+
void doA(){encoder.handleA();}
19+
void doB(){encoder.handleB();}
1720

1821
void setup() {
1922
// debugging port
2023
Serial.begin(115200);
2124

2225
// check if you need internal pullups
23-
// Pullup::EXTERN - external pullup added
26+
// Pullup::EXTERN - external pullup added - dafault
2427
// Pullup::INTERN - needs internal arduino pullup
2528
encoder.pullup = Pullup::EXTERN;
29+
2630
// initialise encoder hardware
27-
encoder.init();
28-
29-
// interupt intitialisation
30-
// A callback and B callback
31-
attachInterrupt(digitalPinToInterrupt(encoder.pinA), []() {
32-
encoder.handleA();
33-
}, CHANGE);
34-
attachInterrupt(digitalPinToInterrupt(encoder.pinB), []() {
35-
encoder.handleB();
36-
}, CHANGE);
37-
31+
encoder.init(doA, doB);
3832

3933
// set driver type
4034
// DriverType::unipolar
@@ -61,7 +55,6 @@ void setup() {
6155
motor.linkEncoder(&encoder);
6256
// intialise motor
6357
motor.init();
64-
motor.enable();
6558
// align encoder and start FOC
6659
motor.initFOC();
6760

examples/velocity_control_serial/velocity_control_serial.ino

Lines changed: 5 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -18,27 +18,21 @@ BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8);
1818
// - cpr - counts per rotation (cpm=ppm*4)
1919
// - index pin - (optional input)
2020
Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 32768, 4);
21+
// interrupt ruotine intialisation
22+
void doA(){encoder.handleA();}
23+
void doB(){encoder.handleB();}
2124

2225
void setup() {
2326
// debugging port
2427
Serial.begin(115200);
2528

26-
2729
// check if you need internal pullups
2830
// Pullup::EXTERN - external pullup added
2931
// Pullup::INTERN - needs internal arduino pullup
3032
encoder.pullup = Pullup::EXTERN;
33+
3134
// initialise encoder hardware
32-
encoder.init();
33-
34-
// interupt intitialisation
35-
// A callback and B callback
36-
attachInterrupt(digitalPinToInterrupt(encoder.pinA), []() {
37-
encoder.handleA();
38-
}, CHANGE);
39-
attachInterrupt(digitalPinToInterrupt(encoder.pinB), []() {
40-
encoder.handleB();
41-
}, CHANGE);
35+
encoder.init(doA, doB);
4236

4337
// set driver type
4438
// DriverType::unipolar
@@ -66,7 +60,6 @@ void setup() {
6660

6761
// intialise motor
6862
motor.init();
69-
motor.enable();
7063
// align encoder and start FOC
7164
motor.initFOC();
7265

examples/velocity_ultraslow_control_serial/velocity_ultraslow_control_serial.ino

Lines changed: 5 additions & 12 deletions
Original file line numberDiff line numberDiff line change
@@ -18,27 +18,21 @@ BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8);
1818
// - cpr - counts per rotation (cpm=ppm*4)
1919
// - index pin - (optional input)
2020
Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 32768, 4);
21+
// interrupt ruotine intialisation
22+
void doA(){encoder.handleA();}
23+
void doB(){encoder.handleB();}
2124

2225
void setup() {
2326
// debugging port
2427
Serial.begin(115200);
2528

26-
2729
// check if you need internal pullups
2830
// Pullup::EXTERN - external pullup added
2931
// Pullup::INTERN - needs internal arduino pullup
3032
encoder.pullup = Pullup::EXTERN;
33+
3134
// initialise encoder hardware
32-
encoder.init();
33-
34-
// interupt intitialisation
35-
// A callback and B callback
36-
attachInterrupt(digitalPinToInterrupt(encoder.pinA), []() {
37-
encoder.handleA();
38-
}, CHANGE);
39-
attachInterrupt(digitalPinToInterrupt(encoder.pinB), []() {
40-
encoder.handleB();
41-
}, CHANGE);
35+
encoder.init(doA, doB);
4236

4337
// set driver type
4438
// DriverType::unipolar
@@ -66,7 +60,6 @@ void setup() {
6660

6761
// intialise motor
6862
motor.init();
69-
motor.enable();
7063
// align encoder and start FOC
7164
motor.initFOC();
7265

0 commit comments

Comments
 (0)