SimpleFOClibrary 2.4.0
Loading...
Searching...
No Matches
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
7
8/**
9 * Step/Dir listenner class for easier interraction with this communication interface.
10 */
12{
13 public:
14
15 /**
16 * Constructor for step/direction interface
17 * @param step - pin
18 * @param direction - pin
19 * @param counter_to_value - step counter to value
20 */
21 StepDirListener(int pinStep, int pinDir, float counter_to_value = 1);
22 /**
23 * Start listenning for step commands
24 *
25 * @param handleStep - on step received handler
26 */
27 void enableInterrupt(void (*handleStep)());
28
29 /**
30 * Initialise dir and step commands
31 */
32 void init();
33 /**
34 * step handler
35 */
36 void handle();
37 /**
38 * Get so far received valued
39 */
40 float getValue();
41 /**
42 * Attach the value to be updated on each step receive
43 * - no need to call getValue function
44 */
45 void attach(float* variable);
46
47 // variables
48 int pin_step; //!< step pin
49 int pin_dir; //!< direction pin
50 long count; //!< current counter value - should be set to 0 for homing
51 decltype(RISING) polarity = RISING; //!< polarity of the step pin
52
53 private:
54 float* attached_variable = nullptr; //!< pointer to the attached variable
55 float counter_to_value; //!< step counter to value
56 //bool step_active = 0; //!< current step pin status (HIGH/LOW) - debouncing variable
57
58};
59
60#endif
void attach(float *variable)
int pin_step
step pin
decltype(RISING) polarity
polarity of the step pin
void enableInterrupt(void(*handleStep)())
int pin_dir
direction pin
long count
current counter value - should be set to 0 for homing