Skip to content

Commit d804971

Browse files
committed
FEAT changed step-dir constructor form step2rotation to count2value
1 parent 8809922 commit d804971

File tree

5 files changed

+12
-12
lines changed

5 files changed

+12
-12
lines changed

examples/utils/communication_test/step_dir/step_dir_listener_simple/step_dir_listener_simple.ino

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -8,8 +8,8 @@
88
// angle
99
float received_angle = 0;
1010

11-
// StepDirListener( step_pin, dir_pin, counts_per_revolution)
12-
StepDirListener step_dir = StepDirListener(2, 3, 200);
11+
// StepDirListener( step_pin, dir_pin, counter_to_value)
12+
StepDirListener step_dir = StepDirListener(2, 3, 360.0/200.0); // receive the angle in degrees
1313
void onStep() { step_dir.handle(); }
1414

1515
void setup() {

examples/utils/communication_test/step_dir/step_dir_listener_software_interrupt/step_dir_listener_software_interrupt.ino

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -13,8 +13,8 @@
1313
// angle
1414
float received_angle = 0;
1515

16-
// StepDirListener( step_pin, dir_pin, counts_per_revolution)
17-
StepDirListener step_dir = StepDirListener(4, 5, 200);
16+
// StepDirListener( step_pin, dir_pin, counter_to_value)
17+
StepDirListener step_dir = StepDirListener(4, 5, 2.0*_PI/200.0); // receive the angle in radians
1818
void onStep() { step_dir.handle(); }
1919

2020
// If no available hadware interrupt pins use the software interrupt

examples/utils/communication_test/step_dir/step_dir_motor_example/step_dir_motor_example.ino

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -18,8 +18,8 @@ Encoder encoder = Encoder(2, 3, 500);
1818
void doA() { encoder.handleA(); }
1919
void doB() { encoder.handleB(); }
2020

21-
// StepDirListener( step_pin, dir_pin, counts_per_revolution)
22-
StepDirListener step_dir = StepDirListener(A4, A5, 200);
21+
// StepDirListener( step_pin, dir_pin, counter_to_value)
22+
StepDirListener step_dir = StepDirListener(A4, A5, 2.0*_PI/200);
2323
void onStep() { step_dir.handle(); }
2424

2525
void setup() {

src/communication/StepDirListener.cpp

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -1,9 +1,9 @@
11
#include "StepDirListener.h"
22

3-
StepDirListener::StepDirListener(int _pinStep, int _pinDir, float _step_per_rotation){
3+
StepDirListener::StepDirListener(int _pinStep, int _pinDir, float _counter_to_value){
44
pin_step = _pinStep;
55
pin_dir = _pinDir;
6-
step_per_rotation = _step_per_rotation;
6+
counter_to_value = _counter_to_value;
77
}
88

99
void StepDirListener::init(){
@@ -36,5 +36,5 @@ void StepDirListener::handle(){
3636
}
3737
// calculate the position from counter
3838
float StepDirListener::getValue(){
39-
return (float) count / step_per_rotation * _2PI;
39+
return (float) count * counter_to_value;
4040
}

src/communication/StepDirListener.h

Lines changed: 3 additions & 3 deletions
Original file line numberDiff line numberDiff line change
@@ -15,9 +15,9 @@ class StepDirListener
1515
* Constructor for step/direction interface
1616
* @param step - pin
1717
* @param direction - pin
18-
* @param step_per_rotation - number of steps per motor rotation
18+
* @param counter_to_value - step counter to value
1919
*/
20-
StepDirListener(int pinStep, int pinDir, float step_per_rotation = 1);
20+
StepDirListener(int pinStep, int pinDir, float counter_to_value = 1);
2121
/**
2222
* Start listenning for step commands
2323
*
@@ -50,7 +50,7 @@ class StepDirListener
5050

5151
private:
5252
float* attached_variable = nullptr; //!< pointer to the attached variable
53-
long step_per_rotation; //!< number of steps per rotation
53+
float counter_to_value; //!< step counter to value
5454
bool step_active = 0; //!< current step pin status (HIGH/LOW) - debouncing variable
5555
};
5656

0 commit comments

Comments
 (0)