SimpleFOClibrary 2.4.0
Loading...
Searching...
No Matches
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
10/**
11 * Quadrature mode configuration structure
12 */
13enum Quadrature : uint8_t {
14 ON = 0x00, //!< Enable quadrature mode CPR = 4xPPR
15 OFF = 0x01 //!< Disable quadrature mode / CPR = PPR
16};
17
18class Encoder: public Sensor{
19 public:
20 /**
21 Encoder class constructor
22 @param encA encoder B pin
23 @param encB encoder B pin
24 @param ppr impulses per rotation (cpr=ppr*4)
25 @param index index pin number (optional input)
26 */
27 Encoder(int encA, int encB , float ppr, int index = 0);
28
29 /** encoder initialise pins */
30 void init() override;
31 /**
32 * function enabling hardware interrupts for the encoder channels with provided callback functions
33 * if callback is not provided then the interrupt is not enabled
34 *
35 * @param doA pointer to the A channel interrupt handler function
36 * @param doB pointer to the B channel interrupt handler function
37 * @param doIndex pointer to the Index channel interrupt handler function
38 *
39 */
40 void enableInterrupts(void (*doA)() = nullptr, void(*doB)() = nullptr, void(*doIndex)() = nullptr);
41
42 // Encoder interrupt callback functions
43 /** A channel callback function */
44 void handleA();
45 /** B channel callback function */
46 void handleB();
47 /** Index channel callback function */
48 void handleIndex();
49
50
51 // pins A and B
52 int pinA; //!< encoder hardware pin A
53 int pinB; //!< encoder hardware pin B
54 int index_pin; //!< index pin
55
56 // Encoder configuration
57 Pullup pullup; //!< Configuration parameter internal or external pullups
58 Quadrature quadrature;//!< Configuration parameter enable or disable quadrature mode
59 float cpr;//!< encoder cpr number
60
61 // Abstract functions of the Sensor class implementation
62 /** get current angle (rad) */
63 float getSensorAngle() override;
64 /** get current angular velocity (rad/s) */
65 float getVelocity() override;
66 virtual void update() override;
67
68 /**
69 * returns 0 if it does need search for absolute zero
70 * 0 - encoder without index
71 * 1 - encoder with index
72 */
73 int needsSearch() override;
74
75 private:
76 int hasIndex(); //!< function returning 1 if encoder has index pin and 0 if not.
77
78 volatile long pulse_counter;//!< current pulse counter
79 volatile long pulse_timestamp;//!< last impulse timestamp in us
80 volatile int A_active; //!< current active states of A channel
81 volatile int B_active; //!< current active states of B channel
82 volatile int I_active; //!< current active states of Index channel
83 volatile bool index_found = false; //!< flag stating that the index has been found
84
85 // velocity calculation variables
86 float prev_Th, pulse_per_second;
87 volatile long prev_pulse_counter, prev_timestamp_us;
88};
89
90
91#endif
Quadrature
Definition Encoder.h:13
@ ON
Enable quadrature mode CPR = 4xPPR.
Definition Encoder.h:14
@ OFF
Disable quadrature mode / CPR = PPR.
Definition Encoder.h:15
Pullup
Definition Sensor.h:19
void handleA()
Definition Encoder.cpp:42
void init() override
Definition Encoder.cpp:181
float getVelocity() override
Definition Encoder.cpp:127
void handleB()
Definition Encoder.cpp:63
Quadrature quadrature
Configuration parameter enable or disable quadrature mode.
Definition Encoder.h:58
void enableInterrupts(void(*doA)()=nullptr, void(*doB)()=nullptr, void(*doIndex)()=nullptr)
Definition Encoder.cpp:212
float cpr
encoder cpr number
Definition Encoder.h:59
int index_pin
index pin
Definition Encoder.h:54
float getSensorAngle() override
Definition Encoder.cpp:117
void handleIndex()
Definition Encoder.cpp:85
int pinA
encoder hardware pin A
Definition Encoder.h:52
Pullup pullup
Configuration parameter internal or external pullups.
Definition Encoder.h:57
int needsSearch() override
Definition Encoder.cpp:169
virtual void update() override
Definition Encoder.cpp:103
int pinB
encoder hardware pin B
Definition Encoder.h:53