-
Notifications
You must be signed in to change notification settings - Fork 0
Expand file tree
/
Copy pathencoders.h
More file actions
252 lines (197 loc) · 8.29 KB
/
encoders.h
File metadata and controls
252 lines (197 loc) · 8.29 KB
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
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
244
245
246
247
248
249
250
251
252
#ifndef _ENCODERS_H
#define _ENCODERS_H
#define ENCODER_0_A_PIN 7
#define ENCODER_0_B_PIN 23
#define ENCODER_1_A_PIN 26
//#define ENCODER_1_B_PIN Non-standard pin!
// Volatile Global variables used by Encoder ISR.
volatile long count_r; // used by encoder to count the rotation
volatile byte state_e0;
volatile long count_l;
volatile byte state_e1;
// This ISR handles just Encoder 1
// ISR to read the Encoder1 Channel A and B pins
// and then look up based on transition what kind of
// rotation must have occured.
ISR( INT6_vect ) {
// We know that the ISR is only called when a pin changes.
// We also know only 1 pin can change at a time.
// The XOR(AB) signal change from "Channel A" triggers ISR.
// First, Read in the new state of the encoder pins.
// Standard pins, so standard read functions.
boolean e0_B = digitalRead( ENCODER_0_B_PIN ); // normal B state
boolean e0_A = digitalRead( ENCODER_0_A_PIN ); // XOR(AB)
// Software XOR (^) logically infers
// the true value of A given the state of B
e0_A = e0_A ^ e0_B;
// Shift our (new) current readings into bit positions
// 2 and 3 in the state variable (current state)
// State: (bit3) (bit2) (bit1) (bit0)
// State: new B new A old B old A
state_e0 = state_e0 | ( e0_B << 3 );
state_e0 = state_e0 | ( e0_A << 2 );
// Handle which transition we have registered.
// Complete this if statement as necessary.
// Refer to the labsheet.
if(state_e0 == 2 or state_e0 == 4 or state_e0 == 11 or state_e0 == 13) { //minus 1
count_r++;
}
else if(state_e0 == 1 or state_e0 == 7 or state_e0 == 8 or state_e0 == 14) { //plus 1
count_r--;
}
else{
Serial.println("Inexistant state value for encoder 0");
}
// Shift the current readings (bits 3 and 2) down
// into position 1 and 0 (to become prior readings)
// This bumps bits 1 and 0 off to the right, "deleting"
// them for the next ISR call.
state_e0 = state_e0 >> 2;
}
// This ISR handles just Encoder 0
// ISR to read the Encoder0 Channel A and B pins
// and then look up based on transition what kind of
// rotation must have occured.
ISR( PCINT0_vect ) {
// First, Read in the new state of the encoder pins.
// Mask for a specific pin from the port.
// Non-standard pin, so we access the register
// directly.
// Reading just PINE would give us a number
// composed of all 8 bits. We want only bit 2.
// B00000100 masks out all but bit 2
// It is more portable to use the PINE2 keyword.
boolean e1_B = PINE & (1<<PINE2);
//boolean e1_B = PINE & B00000100; // Does same as above.
// Standard read from the other pin.
boolean e1_A = digitalRead( ENCODER_1_A_PIN ); // 26 the same as A8
e1_A = e1_A ^ e1_B;
// Create a bitwise representation of our states
// We do this by shifting the boolean value up by
// the appropriate number of bits, as per our table
// header:
//
// State : (bit3) (bit2) (bit1) (bit0)
// State : New A, New B, Old A, Old B.
state_e1 = state_e1 | ( e1_B << 3 );
state_e1 = state_e1 | ( e1_A << 2 );
// Handle which transition we have registered.
// Complete this if statement as necessary.
// Refer to the labsheet.
if(state_e1 == 2 or state_e1 == 4 or state_e1 == 11 or state_e1 == 13) { //minus 1
count_l++;
}
else if(state_e1 == 1 or state_e1 == 7 or state_e1 == 8 or state_e1 == 14) { //plus 1
count_l--;
}
else{
Serial.println("Inexistant state value for encoder 1");
}
// Shift the current readings (bits 3 and 2) down
// into position 1 and 0 (to become prior readings)
// This bumps bits 1 and 0 off to the right, "deleting"
// them for the next ISR call.
state_e1 = state_e1 >> 2;
}
/*
This setup routine enables interrupts for
encoder1. The interrupt is automatically
triggered when one of the encoder pin changes.
This is really convenient! It means we don't
have to check the encoder manually.
*/
void setupEncoder0(){
count_r = 0;
// Setup pins for right encoder
pinMode( ENCODER_0_A_PIN, INPUT );
pinMode( ENCODER_0_B_PIN, INPUT );
// initialise the recorded state of e0 encoder.
state_e0 = 0;
// Get initial state of encoder pins A + B
boolean e0_A = digitalRead( ENCODER_0_A_PIN );
boolean e0_B = digitalRead( ENCODER_0_B_PIN );
e0_A = e0_A ^ e0_B;
// Shift values into correct place in state.
// Bits 1 and 0 are prior states.
state_e0 = state_e0 | ( e0_B << 1 );
state_e0 = state_e0 | ( e0_A << 0 );
// Now to set up PE6 as an external interupt (INT6), which means it can
// have its own dedicated ISR vector INT6_vector
// Page 90, 11.1.3 External Interrupt Mask Register – EIMSK
// Disable external interrupts for INT6 first
// Set INT6 bit low, preserve other bits
EIMSK = EIMSK & ~(1<<INT6);
//EIMSK = EIMSK & B1011111; // Same as above.
// Page 89, 11.1.2 External Interrupt Control Register B – EICRB
// Used to set up INT6 interrupt
EICRB |= ( 1 << ISC60 ); // using header file names, push 1 to bit ISC60
//EICRB |= B00010000; // does same as above
// Page 90, 11.1.4 External Interrupt Flag Register – EIFR
// Setting a 1 in bit 6 (INTF6) clears the interrupt flag.
EIFR |= ( 1 << INTF6 );
//EIFR |= B01000000; // same as above
// Now that we have set INT6 interrupt up, we can enable
// the interrupt to happen
// Page 90, 11.1.3 External Interrupt Mask Register – EIMSK
// Disable external interrupts for INT6 first
// Set INT6 bit high, preserve other bits
EIMSK |= ( 1 << INT6 );
//EIMSK |= B01000000; // Same as above
}
void setupEncoder1(){
count_l = 0;
// Setting up left encoder:
// The Romi board uses the pin PE2 (port E, pin 2) which is
// very unconventional. It doesn't have a standard
// arduino alias (like d6, or a5, for example).
// We set it up here with direct register access
// Writing a 0 to a DDR sets as input
// DDRE = Data Direction Register (Port)E
// We want pin PE2, which means bit 2 (counting from 0)
// PE Register bits [ 7 6 5 4 3 2 1 0 ]
// Binary mask [ 1 1 1 1 1 0 1 1 ]
//
// By performing an & here, the 0 sets low, all 1's preserve
// any previous state.
DDRE = DDRE & ~(1<<DDE6);
//DDRE = DDRE & B11111011; // Same as above.
// We need to enable the pull up resistor for the pin
// To do this, once a pin is set to input (as above)
// You write a 1 to the bit in the output register
PORTE = PORTE | (1 << PORTE2 );
//PORTE = PORTE | 0B00000100;
// Encoder0 uses conventional pin 26
pinMode( ENCODER_1_A_PIN, INPUT );
digitalWrite( ENCODER_1_A_PIN, HIGH ); // Encoder 1 xor
// initialise the recorded state of e1 encoder.
state_e1 = 0;
// Get initial state of encoder.
boolean e1_B = PINE & (1<<PINE2);
//boolean e1_B = PINE & B00000100; // Does same as above.
// Standard read from the other pin.
boolean e1_A = digitalRead( ENCODER_1_A_PIN ); // 26 the same as A8
// Some clever electronics combines the
// signals and this XOR restores the
// true value.
e1_A = e1_A ^ e1_B;
// Enable pin-change interrupt on A8 (PB4) for encoder0, and disable other
// pin-change interrupts.
// Note, this register will normally create an interrupt a change to any pins
// on the port, but we use PCMSK0 to set it only for PCINT4 which is A8 (PB4)
// When we set these registers, the compiler will now look for a routine called
// ISR( PCINT0_vect ) when it detects a change on the pin. PCINT0 seems like a
// mismatch to PCINT4, however there is only the one vector servicing a change
// to all PCINT0->7 pins.
// See Manual 11.1.5 Pin Change Interrupt Control Register - PCICR
// Page 91, 11.1.5, Pin Change Interrupt Control Register
// Disable interrupt first
PCICR = PCICR & ~( 1 << PCIE0 );
// PCICR &= B11111110; // Same as above
// 11.1.7 Pin Change Mask Register 0 – PCMSK0
PCMSK0 |= (1 << PCINT4);
// Page 91, 11.1.6 Pin Change Interrupt Flag Register – PCIFR
PCIFR |= (1 << PCIF0); // Clear its interrupt flag by writing a 1.
// Enable
PCICR |= (1 << PCIE0);
}
#endif