SimpleFOClibrary  2.1
StepDirListener.h
Go to the documentation of this file.
1 #ifndef STEPDIR_H
2 #define STEPDIR_H
3 
4 #include "Arduino.h"
5 #include "../common/foc_utils.h"
6 
11 {
12  public:
13 
20  StepDirListener(int pinStep, int pinDir, float counter_to_value = 1);
26  void enableInterrupt(void (*handleStep)());
27 
31  void init();
35  void handle();
39  float getValue();
44  void attach(float* variable);
45 
46  // variables
47  int pin_step;
48  int pin_dir;
49  long count;
50 
51  private:
52  float* attached_variable = nullptr;
53  float counter_to_value;
54  bool step_active = 0;
55 };
56 
57 #endif
StepDirListener::pin_dir
int pin_dir
direction pin
Definition: StepDirListener.h:48
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
Definition: StepDirListener.h:11
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