SimpleFOClibrary  2.1
Encoder.h
Go to the documentation of this file.
1 #ifndef ENCODER_LIB_H
2 #define ENCODER_LIB_H
3 
4 #include "Arduino.h"
5 #include "../common/foc_utils.h"
6 #include "../common/time_utils.h"
7 #include "../common/base_classes/Sensor.h"
8 
9 
14  ON,
15  OFF
16 };
17 
18 class Encoder: public Sensor{
19  public:
27  Encoder(int encA, int encB , float ppr, int index = 0);
28 
30  void init();
40  void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doIndex)() = nullptr);
41 
42  // Encoder interrupt callback functions
44  void handleA();
46  void handleB();
48  void handleIndex();
49 
50 
51  // pins A and B
52  int pinA;
53  int pinB;
54  int index_pin;
55 
56  // Encoder configuration
59  float cpr;
60 
61  // Abstract functions of the Sensor class implementation
63  float getAngle() override;
65  float getVelocity() override;
71  int needsSearch() override;
72 
73  private:
74  int hasIndex();
75 
76  volatile long pulse_counter;
77  volatile long pulse_timestamp;
78  volatile int A_active;
79  volatile int B_active;
80  volatile int I_active;
81  volatile bool index_found = false;
82 
83  // velocity calculation variables
84  float prev_Th, pulse_per_second;
85  volatile long prev_pulse_counter, prev_timestamp_us;
86 };
87 
88 
89 #endif
Encoder::pinA
int pinA
encoder hardware pin A
Definition: Encoder.h:52
Quadrature
Quadrature
Definition: Encoder.h:13
Encoder::Encoder
Encoder(int encA, int encB, float ppr, int index=0)
Definition: Encoder.cpp:11
Encoder::index_pin
int index_pin
index pin
Definition: Encoder.h:54
Encoder::handleIndex
void handleIndex()
Definition: Encoder.cpp:85
Encoder::handleB
void handleB()
Definition: Encoder.cpp:63
ON
@ ON
Enable quadrature mode CPR = 4xPPR.
Definition: Encoder.h:14
Encoder::init
void init()
Definition: Encoder.cpp:160
Encoder::enableInterrupts
void enableInterrupts(void(*doA)()=nullptr, void(*doB)()=nullptr, void(*doIndex)()=nullptr)
Definition: Encoder.cpp:190
Encoder::pullup
Pullup pullup
Configuration parameter internal or external pullups.
Definition: Encoder.h:57
OFF
@ OFF
Disable quadrature mode / CPR = PPR.
Definition: Encoder.h:15
Pullup
Pullup
Definition: Sensor.h:17
Encoder
Definition: Encoder.h:18
Encoder::quadrature
Quadrature quadrature
Configuration parameter enable or disable quadrature mode.
Definition: Encoder.h:58
Encoder::cpr
float cpr
encoder cpr number
Definition: Encoder.h:59
Encoder::getVelocity
float getVelocity() override
Definition: Encoder.cpp:111
Encoder::needsSearch
int needsSearch() override
Definition: Encoder.cpp:148
Encoder::handleA
void handleA()
Definition: Encoder.cpp:42
Encoder::getAngle
float getAngle() override
Definition: Encoder.cpp:104
Encoder::pinB
int pinB
encoder hardware pin B
Definition: Encoder.h:53
Sensor
Definition: Sensor.h:26