SimpleFOClibrary 2.4.0
Loading...
Searching...
No Matches
Encoder.cpp
Go to the documentation of this file.
1#include "Encoder.h"
2
3
4/*
5 Encoder(int encA, int encB , int cpr, int index)
6 - encA, encB - encoder A and B pins
7 - cpr - counts per rotation number (cpm=ppm*4)
8 - index pin - (optional input)
9*/
10
11Encoder::Encoder(int _encA, int _encB , float _ppr, int _index){
12
13 // Encoder measurement structure init
14 // hardware pins
15 pinA = _encA;
16 pinB = _encB;
17 // counter setup
18 pulse_counter = 0;
19 pulse_timestamp = 0;
20
21 cpr = _ppr;
22 A_active = 0;
23 B_active = 0;
24 I_active = 0;
25 // index pin
26 index_pin = _index; // its 0 if not used
27
28 // velocity calculation variables
29 prev_Th = 0;
30 pulse_per_second = 0;
31 prev_pulse_counter = 0;
32 prev_timestamp_us = _micros();
33
34 // extern pullup as default
36 // enable quadrature encoder by default
38}
39
40// Encoder interrupt callback functions
41// A channel
43 bool A = digitalRead(pinA);
44 switch (quadrature){
45 case Quadrature::ON:
46 // CPR = 4xPPR
47 if ( A != A_active ) {
48 pulse_counter += (A_active == B_active) ? 1 : -1;
49 pulse_timestamp = _micros();
50 A_active = A;
51 }
52 break;
53 case Quadrature::OFF:
54 // CPR = PPR
55 if(A && !digitalRead(pinB)){
56 pulse_counter++;
57 pulse_timestamp = _micros();
58 }
59 break;
60 }
61}
62// B channel
64 bool B = digitalRead(pinB);
65 switch (quadrature){
66 case Quadrature::ON:
67 // // CPR = 4xPPR
68 if ( B != B_active ) {
69 pulse_counter += (A_active != B_active) ? 1 : -1;
70 pulse_timestamp = _micros();
71 B_active = B;
72 }
73 break;
74 case Quadrature::OFF:
75 // CPR = PPR
76 if(B && !digitalRead(pinA)){
77 pulse_counter--;
78 pulse_timestamp = _micros();
79 }
80 break;
81 }
82}
83
84// Index channel
86 if(hasIndex()){
87 bool I = digitalRead(index_pin);
88 if(I && !I_active){
89 index_found = true;
90 // align encoder on each index
91 long tmp = pulse_counter;
92 // corrent the counter value
93 pulse_counter = round((double)pulse_counter/(double)cpr)*cpr;
94 // preserve relative speed
95 prev_pulse_counter += pulse_counter - tmp;
96 }
97 I_active = I;
98 }
99}
100
101
102// Sensor update function. Safely copy volatile interrupt variables into Sensor base class state variables.
104 // Copy volatile variables in minimal-duration blocking section to ensure no interrupts are missed
105 noInterrupts();
106 angle_prev_ts = pulse_timestamp;
107 long copy_pulse_counter = pulse_counter;
108 interrupts();
109 // TODO: numerical precision issue here if the pulse_counter overflows the angle will be lost
110 full_rotations = copy_pulse_counter / (int)cpr;
111 angle_prev = _2PI * ((copy_pulse_counter) % ((int)cpr)) / ((float)cpr);
112}
113
114/*
115 Shaft angle calculation
116*/
118 return _2PI * (pulse_counter) / ((float)cpr);
119}
120
121
122
123/*
124 Shaft velocity calculation
125 function using mixed time and frequency measurement technique
126*/
128 // Copy volatile variables in minimal-duration blocking section to ensure no interrupts are missed
129 noInterrupts();
130 long copy_pulse_counter = pulse_counter;
131 long copy_pulse_timestamp = pulse_timestamp;
132 interrupts();
133 // timestamp
134 long timestamp_us = _micros();
135 // sampling time calculation
136 float Ts = (timestamp_us - prev_timestamp_us) * 1e-6f;
137 // quick fix for strange cases (micros overflow)
138 if(Ts <= 0 || Ts > 0.5f) Ts = 1e-3f;
139
140 // time from last impulse
141 float Th = (timestamp_us - copy_pulse_timestamp) * 1e-6f;
142 long dN = copy_pulse_counter - prev_pulse_counter;
143
144 // Pulse per second calculation (Eq.3.)
145 // dN - impulses received
146 // Ts - sampling time - time in between function calls
147 // Th - time from last impulse
148 // Th_1 - time form last impulse of the previous call
149 // only increment if some impulses received
150 float dt = Ts + prev_Th - Th;
151 pulse_per_second = (dN != 0 && dt > Ts/2) ? dN / dt : pulse_per_second;
152
153 // if more than 0.05f passed in between impulses
154 if ( Th > 0.1f) pulse_per_second = 0;
155
156 // velocity calculation
157 float velocity = pulse_per_second / ((float)cpr) * (_2PI);
158
159 // save variables for next pass
160 prev_timestamp_us = timestamp_us;
161 // save velocity calculation variables
162 prev_Th = Th;
163 prev_pulse_counter = copy_pulse_counter;
164 return velocity;
165}
166
167// getter for index pin
168// return -1 if no index
170 return hasIndex() && !index_found;
171}
172
173// private function used to determine if encoder has index
174int Encoder::hasIndex(){
175 return index_pin != 0;
176}
177
178
179// encoder initialisation of the hardware pins
180// and calculation variables
182
183 // Encoder - check if pullup needed for your encoder
185 pinMode(pinA, INPUT_PULLUP);
186 pinMode(pinB, INPUT_PULLUP);
187 if(hasIndex()) pinMode(index_pin,INPUT_PULLUP);
188 }else{
189 pinMode(pinA, INPUT);
190 pinMode(pinB, INPUT);
191 if(hasIndex()) pinMode(index_pin,INPUT);
192 }
193
194 // counter setup
195 pulse_counter = 0;
196 pulse_timestamp = _micros();
197 // velocity calculation variables
198 prev_Th = 0;
199 pulse_per_second = 0;
200 prev_pulse_counter = 0;
201 prev_timestamp_us = _micros();
202
203 // initial cpr = PPR
204 // change it if the mode is quadrature
205 if(quadrature == Quadrature::ON) cpr = 4*cpr;
206
207 // we don't call Sensor::init() here because init is handled in Encoder class.
208}
209
210// function enabling hardware interrupts of the for the callback provided
211// if callback is not provided then the interrupt is not enabled
212void Encoder::enableInterrupts(void (*doA)(), void(*doB)(), void(*doIndex)()){
213 // attach interrupt if functions provided
214 switch(quadrature){
215 case Quadrature::ON:
216 // A callback and B callback
217 if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, CHANGE);
218 if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, CHANGE);
219 break;
220 case Quadrature::OFF:
221 // A callback and B callback
222 if(doA != nullptr) attachInterrupt(digitalPinToInterrupt(pinA), doA, RISING);
223 if(doB != nullptr) attachInterrupt(digitalPinToInterrupt(pinB), doB, RISING);
224 break;
225 }
226
227 // if index used initialize the index interrupt
228 if(hasIndex() && doIndex != nullptr) attachInterrupt(digitalPinToInterrupt(index_pin), doIndex, CHANGE);
229}
@ ON
Enable quadrature mode CPR = 4xPPR.
Definition Encoder.h:14
@ OFF
Disable quadrature mode / CPR = PPR.
Definition Encoder.h:15
@ USE_EXTERN
Use external pullups.
Definition Sensor.h:21
@ USE_INTERN
Use internal pullups.
Definition Sensor.h:20
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
Encoder(int encA, int encB, float ppr, int index=0)
Definition Encoder.cpp:11
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
float velocity
Definition Sensor.h:130
long angle_prev_ts
Definition Sensor.h:132
int32_t full_rotations
Definition Sensor.h:135
float angle_prev
Definition Sensor.h:131
#define _2PI
Definition foc_utils.h:29
unsigned long _micros()