-
Notifications
You must be signed in to change notification settings - Fork 9
/
quadrature.h
219 lines (183 loc) · 5.14 KB
/
quadrature.h
1
2
3
4
5
6
7
8
9
10
11
12
13
14
15
16
17
18
19
20
21
22
23
24
25
26
27
28
29
30
31
32
33
34
35
36
37
38
39
40
41
42
43
44
45
46
47
48
49
50
51
52
53
54
55
56
57
58
59
60
61
62
63
64
65
66
67
68
69
70
71
72
73
74
75
76
77
78
79
80
81
82
83
84
85
86
87
88
89
90
91
92
93
94
95
96
97
98
99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
#ifndef QUADRATURE_H
#define QUADRATURE_H OCT_2014
#include <Arduino.h>
/*
A quadrature encoder library for Arduino that takes
advantage of inturrept processing to track direction
and counts for a shaft.
See the link below for the best explanation of quadrature I've found
on the web.
http://letsmakerobots.com/node/24031
EDIT 3/17/2016: This link is no longer active.
See the following link for a similar description, but Oddbot doesn't seem to get a credit
at this link althought it looks just like his work.
http://www.robotshop.com/media/files/PDF/tutorial-how-to-use-a-quadrature-encoder-rs011a.pdf
I've adapted the code from OdddBot to be interupt driven, and added
a counter.
*/
namespace Motion {
enum motion{frwd, back, stop};
const char res0[5] = "frwd";
const char res1[5] = "back";
const char res2[5] = "stop";
inline const char* text(motion m) {
const char* res;
switch(m) {
case frwd:
res = res0;
break;
case back:
res = res1;
break;
case stop:
res = res2;
break;
}
return res;
}
}
namespace Board {
enum board{uno, due};
}
namespace QEM {
//Quadrature Encoder Matrix from OddBot
const int qem[16] = {0,-1,1,2,1,0,2,-1,-1,2,0,1,2,1,-1,0};
}
template<int A, int B>
class Quadrature_encoder {
public:
//Constructor
Quadrature_encoder<A, B>(Board::board b = Board::uno) {};
// Must be called in the sketch Setup
void begin();
// count() return the total counts accumulated by the encoder
long count() {return ct;}
// motion() returns whether the encoder has moved forward, backward,
// or is motionless SINCE THE LAST TIME MOTION WAS CALLED.
Motion::motion motion();
//invert the output of .motion for the same direction of
//physical rotation of the shaft. The simplest way to achieve
//this is to swap the two encoder pins. However, if you have the
//shaft encoder pins plugged into a PCB or header that prevents
//swapping the input pins then calling .reverse() in the setup
//of your sketch will give you the correct output from subsequent
//calls to .motion()
void reverse() { r = !r; }
private:
Board::board b;
static const int A_pin = A;
static const int B_pin = B;
static volatile byte Enc_A;
static volatile byte Enc_B;
static volatile int out_val, old_reading, new_reading;
static volatile long ct;
static long old_ct;
static bool r;
int pin_A_digital;
int pin_B_digital;
// ISR's
static void delta_A();
static void delta_B();
};
template<int A, int B> volatile byte Quadrature_encoder<A, B>::Enc_A = LOW;
template<int A, int B> volatile byte Quadrature_encoder<A, B>::Enc_B = LOW;
template<int A, int B> volatile int Quadrature_encoder<A, B>::out_val = 0;
template<int A, int B> volatile int Quadrature_encoder<A, B>::old_reading = 0;
template<int A, int B> volatile int Quadrature_encoder<A, B>::new_reading = 0;
template<int A, int B> volatile long Quadrature_encoder<A, B>::ct = 0;
template<int A, int B> long Quadrature_encoder<A, B>::old_ct = 0;
template<int A, int B> bool Quadrature_encoder<A, B>::r = false;
template<int A, int B>
inline
void Quadrature_encoder<A, B>::begin()
{
//store the starting state for the two interrupt pins
if(b == Board::uno) {
if (A_pin == 0) {
pin_A_digital = 2;
pin_B_digital = 3;
} else {
pin_A_digital = 3;
pin_B_digital = 2;
}
}
if(b == Board::due) {
pin_A_digital = A_pin;
pin_B_digital = B_pin;
}
/*
TODO: Add mega support
*/
pinMode(pin_A_digital, INPUT);
pinMode(pin_B_digital, INPUT);
Enc_A = digitalRead(pin_A_digital);
Enc_B = digitalRead(pin_B_digital);
//configure the interrupts
attachInterrupt(A_pin, &Quadrature_encoder<A,B>::delta_A, CHANGE);
attachInterrupt(B_pin, &Quadrature_encoder<A,B>::delta_B, CHANGE);
}
template<int A, int B>
inline
Motion::motion Quadrature_encoder<A, B>::motion()
{
Motion::motion res;
long new_count = count();
long delta = new_count - old_ct;
if(delta > 0) {
res = Motion::frwd;
}
else if (delta < 0){
res = Motion::back;
}
else if (delta == 0){
res = Motion::stop;
}
//set up for the next call
old_ct = new_count;
return res;
}
template<int A, int B>
inline
void Quadrature_encoder<A, B>::delta_A()
{
old_reading = new_reading;
Enc_A = !Enc_A;
if(r){
new_reading = Enc_A * 2 + Enc_B;
}
else {
new_reading = Enc_B * 2 + Enc_A;
}
out_val = QEM::qem [old_reading * 4 + new_reading];
switch(out_val){
case 1:
++ct;
break;
case -1:
--ct;
break;
}
}
template<int A, int B>
inline
void Quadrature_encoder<A, B>::delta_B()
{
old_reading = new_reading;
Enc_B = !Enc_B;
if(r){
new_reading = Enc_A * 2 + Enc_B;
}
else {
new_reading = Enc_B * 2 + Enc_A;
}
out_val = QEM::qem [old_reading * 4 + new_reading];
switch(out_val){
case 1:
++ct;
break;
case -1:
--ct;
break;
}
}
#endif