|
10 | 10 | BLDCMotor motor = BLDCMotor(9, 10, 11, 11); |
11 | 11 | // Encoder(int encA, int encB , int cpr, int index) |
12 | 12 | // - encA, encB - encoder A and B pins |
13 | | -// - cpr - counts per rotation (cpm=ppm*4) |
| 13 | +// - ppr - impulses per rotation (cpr=ppr*4) |
14 | 14 | // - 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();} |
17 | 19 |
|
18 | 20 | // 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); |
25 | 23 |
|
26 | 24 | void setup() { |
27 | 25 | // debugging port |
28 | 26 | Serial.begin(115200); |
29 | 27 |
|
30 | | - |
31 | 28 | // check if you need internal pullups |
32 | 29 | // Pullup::EXTERN - external pullup added |
33 | 30 | // Pullup::INTERN - needs internal arduino pullup |
34 | | - encoder.pullup = Pullup::EXTERN; |
| 31 | + encoder.pullup = Pullup::INTERN; |
35 | 32 | // initialise encoder hardware |
36 | 33 | encoder.init(); |
37 | 34 |
|
38 | | - |
39 | | - // interupt intitialisation |
| 35 | + // interrupt intitialisation |
40 | 36 | PciManager.registerListener(&listenerA); |
41 | 37 | PciManager.registerListener(&listenerB); |
42 | 38 |
|
@@ -66,7 +62,6 @@ void setup() { |
66 | 62 |
|
67 | 63 | // intialise motor |
68 | 64 | motor.init(); |
69 | | - motor.enable(); |
70 | 65 | // align encoder and start FOC |
71 | 66 | motor.initFOC(); |
72 | 67 |
|
|
0 commit comments