Skip to content

Commit df3c78d

Browse files
committed
cpr to ppr
1 parent bd42747 commit df3c78d

File tree

9 files changed

+18
-18
lines changed

9 files changed

+18
-18
lines changed

Encoder.cpp

Lines changed: 2 additions & 2 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;

Encoder.h

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,10 +15,10 @@ 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

2323
// encoder initialise pins
2424
void init(void (*doA)() = nullptr, void(*doB)() = nullptr);

examples/HMBGC_example/HMBGC_example.ino

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -10,9 +10,9 @@
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);
15+
Encoder encoder = Encoder(A1, A0, 600);
1616
// interrupt ruotine intialisation
1717
void doA(){encoder.handleA();}
1818
void doB(){encoder.handleB();}

examples/angle_control/angle_control.ino

Lines changed: 2 additions & 2 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();}

examples/angle_control_serial/angle_control_serial.ino

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -14,9 +14,9 @@ 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);
2020
// interrupt ruotine intialisation
2121
void doA(){encoder.handleA();}
2222
void doB(){encoder.handleB();}

examples/minimal_example/minimal_example.ino

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -10,8 +10,8 @@
1010

1111
// BLDCMotor( phA, phB, phC, pole_pairs, enable)
1212
BLDCMotor motor = BLDCMotor(9, 10, 11, 11, 8);
13-
// Encoder(encA, encB , cpr, index)
14-
Encoder encoder = Encoder(2, 3, 32768, 4);
13+
// Encoder(encA, encB , ppr, index)
14+
Encoder encoder = Encoder(2, 3, 8192, 4);
1515

1616
// interrupt ruotine intialisation
1717
void doA(){encoder.handleA();}

examples/velocity_control/velocity_control.ino

Lines changed: 2 additions & 2 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();}

examples/velocity_control_serial/velocity_control_serial.ino

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,9 +15,9 @@ 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);
2121
// interrupt ruotine intialisation
2222
void doA(){encoder.handleA();}
2323
void doB(){encoder.handleB();}

examples/velocity_ultraslow_control_serial/velocity_ultraslow_control_serial.ino

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -15,9 +15,9 @@ 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);
2121
// interrupt ruotine intialisation
2222
void doA(){encoder.handleA();}
2323
void doB(){encoder.handleB();}

0 commit comments

Comments
 (0)