![]() |
SimpleFOClibrary
2.1
|
#include <StepDirListener.h>
Public Member Functions | |
StepDirListener (int pinStep, int pinDir, float counter_to_value=1) | |
void | enableInterrupt (void(*handleStep)()) |
void | init () |
void | handle () |
float | getValue () |
void | attach (float *variable) |
Public Attributes | |
int | pin_step |
step pin More... | |
int | pin_dir |
direction pin More... | |
long | count |
current counter value - should be set to 0 for homing More... | |
Step/Dir listenner class for easier interraction with this communication interface.
Definition at line 10 of file StepDirListener.h.
StepDirListener::StepDirListener | ( | int | pinStep, |
int | pinDir, | ||
float | counter_to_value = 1 |
||
) |
Constructor for step/direction interface
step | - pin |
direction | - pin |
counter_to_value | - step counter to value |
Definition at line 3 of file StepDirListener.cpp.
void StepDirListener::attach | ( | float * | variable | ) |
Attach the value to be updated on each step receive
Definition at line 19 of file StepDirListener.cpp.
void StepDirListener::enableInterrupt | ( | void(*)() | handleStep | ) |
Start listenning for step commands
handleStep | - on step received handler |
Definition at line 15 of file StepDirListener.cpp.
float StepDirListener::getValue | ( | ) |
Get so far received valued
Definition at line 38 of file StepDirListener.cpp.
void StepDirListener::handle | ( | ) |
step handler
Definition at line 23 of file StepDirListener.cpp.
void StepDirListener::init | ( | ) |
Initialise dir and step commands
Definition at line 9 of file StepDirListener.cpp.
long StepDirListener::count |
current counter value - should be set to 0 for homing
Definition at line 49 of file StepDirListener.h.
int StepDirListener::pin_dir |
direction pin
Definition at line 48 of file StepDirListener.h.
int StepDirListener::pin_step |
step pin
Definition at line 47 of file StepDirListener.h.