SimpleFOClibrary  2.1
StepDirListener.cpp
Go to the documentation of this file.
1 #include "StepDirListener.h"
2 
3 StepDirListener::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, CHANGE);
17 }
18 
19 void 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 }
StepDirListener::pin_dir
int pin_dir
direction pin
Definition: StepDirListener.h:48
StepDirListener.h
StepDirListener::pin_step
int pin_step
step pin
Definition: StepDirListener.h:47
StepDirListener::enableInterrupt
void enableInterrupt(void(*handleStep)())
Definition: StepDirListener.cpp:15
StepDirListener::init
void init()
Definition: StepDirListener.cpp:9
StepDirListener::handle
void handle()
Definition: StepDirListener.cpp:23
StepDirListener::getValue
float getValue()
Definition: StepDirListener.cpp:38
StepDirListener::count
long count
current counter value - should be set to 0 for homing
Definition: StepDirListener.h:49
StepDirListener::attach
void attach(float *variable)
Definition: StepDirListener.cpp:19
StepDirListener::StepDirListener
StepDirListener(int pinStep, int pinDir, float counter_to_value=1)
Definition: StepDirListener.cpp:3