Skip to content

Commit a69c4f7

Browse files
committed
mrege
2 parents b774a73 + df3c78d commit a69c4f7

File tree

10 files changed

+111
-99
lines changed

10 files changed

+111
-99
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: 10 additions & 16 deletions
Original file line numberDiff line numberDiff line change
@@ -8,7 +8,7 @@
88
- index pin - (optional input)
99
*/
1010

11-
Encoder::Encoder(int _encA, int _encB , float _cpr, int _index){
11+
Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){
1212

1313
// Encoder measurement structure init
1414
// hardware pins
@@ -17,7 +17,7 @@ Encoder::Encoder(int _encA, int _encB , float _cpr, int _index){
1717
// counter setup
1818
pulse_counter = 0;
1919
pulse_timestamp = 0;
20-
cpr = _cpr;
20+
cpr = 4.0*_ppr;
2121
A_active = 0;
2222
B_active = 0;
2323
I_active = 0;
@@ -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: 6 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -15,22 +15,21 @@ class Encoder{
1515
/*
1616
Encoder(int encA, int encB , int cpr, int index)
1717
- encA, encB - encoder A and B pins
18-
- cpr - counts per rotation number (cpm=ppm*4)
18+
- ppr - impulses per rotation (cpr=ppr*4)
1919
- index pin - (optional input)
2020
*/
21-
Encoder(int encA, int encB , float cpr, int index = 0);
21+
Encoder(int encA, int encB , float ppr, 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: 9 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -10,33 +10,29 @@
1010
BLDCMotor motor = BLDCMotor(9, 10, 11, 11);
1111
// Encoder(int encA, int encB , int cpr, int index)
1212
// - encA, encB - encoder A and B pins
13-
// - cpr - counts per rotation (cpm=ppm*4)
13+
// - ppr - impulses per rotation (cpr=ppr*4)
1414
// - index pin - (optional input)
15-
Encoder encoder = Encoder(A1, A0, 2400);
16-
15+
Encoder encoder = Encoder(A1, A0, 600);
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: 2 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -11,9 +11,9 @@
1111
BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8);
1212
// Encoder(int encA, int encB , int cpr, int index)
1313
// - encA, encB - encoder A and B pins
14-
// - cpr - counts per rotation (cpm=ppm*4)
14+
// - ppr - impulses per rotation (cpr=ppr*4)
1515
// - index pin - (optional input)
16-
Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 32768, 4);
16+
Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192, 4);
1717
// interrupt ruotine intialisation
1818
void doA(){encoder.handleA();}
1919
void doB(){encoder.handleB();}
@@ -62,7 +62,6 @@ void setup() {
6262

6363
// intialise motor
6464
motor.init();
65-
motor.enable();
6665
// align encoder and start FOC
6766
motor.initFOC();
6867

examples/angle_control_serial/angle_control_serial.ino

Lines changed: 7 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -14,31 +14,24 @@ float target_angle = 0;
1414
BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8);
1515
// Encoder(int encA, int encB , int cpr, int index)
1616
// - encA, encB - encoder A and B pins
17-
// - cpr - counts per rotation (cpm=ppm*4)
17+
// - ppr - impulses per rotation (cpr=ppr*4)
1818
// - index pin - (optional input)
19-
Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 32768, 4);
19+
Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192, 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

Lines changed: 48 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -0,0 +1,48 @@
1+
#include <ArduinoFOC.h>
2+
3+
// This example gives you a minimal code needed to run the FOC algorithm
4+
// All the configuration is set to defualt values
5+
// motor.power_supply_voltage= 12V
6+
// motor.driver = DriverType::bipolar
7+
// encoder.pullup = Pullup::EXTERN
8+
// motor.PI_velocity.K = 1
9+
// motor.PI_velocity.Ti = 0.003
10+
11+
// BLDCMotor( phA, phB, phC, pole_pairs, enable)
12+
BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8);
13+
// Encoder(encA, encB , ppr, index)
14+
Encoder encoder = Encoder(2, 3, 8192, 4);
15+
16+
// interrupt ruotine intialisation
17+
void doA(){encoder.handleA();}
18+
void doB(){encoder.handleB();}
19+
20+
void setup() {
21+
// debugging port
22+
Serial.begin(115200);
23+
24+
// initialise encoder hardware
25+
encoder.init(doA, doB);
26+
// link the motor to the sensor
27+
motor.linkEncoder(&encoder);
28+
// intialise motor
29+
motor.init();
30+
// velocity control
31+
motor.controller = ControlType::velocity;
32+
// align encoder and start FOC
33+
motor.initFOC();
34+
35+
Serial.println("Motor ready.");
36+
delay(1000);
37+
}
38+
39+
// target velocity variable
40+
float target_velocity = 2;
41+
42+
void loop() {
43+
// foc loop
44+
motor.loopFOC();
45+
// control loop
46+
motor.move(target_velocity);
47+
motor_monitor();
48+
}

examples/velocity_control/velocity_control.ino

Lines changed: 8 additions & 15 deletions
Original file line numberDiff line numberDiff line change
@@ -11,30 +11,24 @@
1111
BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8);
1212
// Encoder(int encA, int encB , int cpr, int index)
1313
// - encA, encB - encoder A and B pins
14-
// - cpr - counts per rotation (cpm=ppm*4)
14+
// - ppr - impulses per rotation (cpr=ppr*4)
1515
// - index pin - (optional input)
16-
Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 32768, 4);
16+
Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192, 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: 7 additions & 14 deletions
Original file line numberDiff line numberDiff line change
@@ -15,30 +15,24 @@ float target_velocity = 0;
1515
BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8);
1616
// Encoder(int encA, int encB , int cpr, int index)
1717
// - encA, encB - encoder A and B pins
18-
// - cpr - counts per rotation (cpm=ppm*4)
18+
// - ppr - impulses per rotation (cpr=ppr*4)
1919
// - index pin - (optional input)
20-
Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 32768, 4);
20+
Encoder encoder = Encoder(arduinoInt1, arduinoInt2, 8192, 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)