SimpleFOClibrary 2.4.0
Loading...
Searching...
No Matches
StepDirListener.cpp
Go to the documentation of this file.
1#include "StepDirListener.h"
2
3StepDirListener::StepDirListener(int _pinStep, int _pinDir, float _counter_to_value){
4 pin_step = _pinStep;
5 pin_dir = _pinDir;
6 counter_to_value = _counter_to_value;
7}
8
10 pinMode(pin_dir, INPUT);
11 pinMode(pin_step, INPUT_PULLUP);
12 count = 0;
13}
14
16 attachInterrupt(digitalPinToInterrupt(pin_step), doA, polarity);
17}
18
19void StepDirListener::attach(float* variable){
20 attached_variable = variable;
21}
22
24 // read step status
25 //bool step = digitalRead(pin_step);
26 // update counter only on rising edge
27 //if(step && step != step_active){
28 if(digitalRead(pin_dir))
29 count++;
30 else
31 count--;
32 //}
33 //step_active = step;
34 // if attached variable update it
35 if(attached_variable) *attached_variable = getValue();
36}
37// calculate the position from counter
39 return (float) count * counter_to_value;
40}
void attach(float *variable)
int pin_step
step pin
decltype(RISING) polarity
polarity of the step pin
StepDirListener(int pinStep, int pinDir, float counter_to_value=1)
void enableInterrupt(void(*handleStep)())
int pin_dir
direction pin
long count
current counter value - should be set to 0 for homing