Revision 1922
Added Dan's line following code
trunk/code/projects/linefollowing/lineFollow.h | ||
---|---|---|
1 | 1 |
#include <dragonfly_lib.h> |
2 | 2 |
|
3 |
#ifndef _LINEFOLLOW_H_ |
|
4 |
#define _LINEFOLLOW_H_ |
|
3 |
#ifndef _LINEFOLLOW_H_
|
|
4 |
#define _LINEFOLLOW_H_
|
|
5 | 5 |
|
6 | 6 |
#define LWHITE 0 |
7 | 7 |
#define LGREY 1 |
8 | 8 |
#define LBLACK 2 |
9 | 9 |
#define CENTER 3 |
10 |
#define NOLINE -42 |
|
10 | 11 |
#define LINELOST -1 |
11 | 12 |
|
12 | 13 |
#define NOBARCODE -2 |
13 |
#define INTERSECTION -25 |
|
14 |
#define INTERSECTION -25 |
|
15 |
#define FULL_LINE -26 |
|
14 | 16 |
|
15 |
#define NOLINE -50 |
|
16 |
#define FULL_LINE -51 |
|
17 | 17 |
|
18 |
/** |
|
19 |
* @brief Initializes line following. |
|
20 |
* |
|
21 |
* Must be called before line following will work. |
|
22 |
* Turns the analog loop off. |
|
23 |
*/ |
|
18 |
|
|
19 |
/* lineFollow_init |
|
20 |
Must call before lineFollow |
|
21 |
Turns analog loop off |
|
22 |
*/ |
|
24 | 23 |
void lineFollow_init(void); |
25 | 24 |
|
26 |
/** lineFollow
|
|
27 |
* Must call lineFollow_init first
|
|
28 |
* Must be called inside a loop
|
|
29 |
*/
|
|
25 |
/* lineFollow |
|
26 |
Must call lineFollow first
|
|
27 |
Must be called inside a loop |
|
28 |
*/ |
|
30 | 29 |
int lineFollow(int speed); |
31 | 30 |
|
32 |
/** turnLeft turnRight mergeLeft mergeRight
|
|
33 |
* Must be called inside a loop
|
|
34 |
* returns 0 when complete
|
|
35 |
*/
|
|
31 |
/* turnLeft turnRight mergeLeft mergeRight |
|
32 |
Must be called inside a loop |
|
33 |
returns 0 when complete |
|
34 |
*/ |
|
36 | 35 |
int turnLeft(void); |
37 | 36 |
int turnRight(void); |
38 | 37 |
int mergeLeft(void); |
39 | 38 |
int mergeRight(void); |
40 | 39 |
|
41 |
/** |
|
42 |
* @brief Updates the values stored in the array to white or black based on |
|
43 |
* current sensor readings. |
|
44 |
* |
|
45 |
* @param values The array of five integers to be updated. |
|
46 |
*/ |
|
40 |
/* updateLine |
|
41 |
Reads in the analog values |
|
42 |
Fills the given array with WHITE |
|
43 |
or BLACK representing the line |
|
44 |
*/ |
|
47 | 45 |
void updateLine(int* values); |
48 | 46 |
|
49 |
/** |
|
50 |
* @brief Returns an index of the middle of the line based on line readings. |
|
51 |
* |
|
52 |
* Two special return values are possible: |
|
53 |
* NOLINE if none of the sensors holds a black value, and |
|
54 |
* FULL_LINE if all of the sensors see black. |
|
55 |
* |
|
56 |
* Otherwise, returns a value from -4 (farthest left) to 4 (farthest right), with |
|
57 |
* 0 the line being centered in the middle. |
|
58 |
* |
|
59 |
* @param colors The array of 5 readings from the line sensor. Must be either |
|
60 |
* LWHITE or LBLACK. |
|
61 |
* @return Either a special value or an index from -4 to 4. |
|
62 |
* |
|
63 |
*/ |
|
47 |
/* lineLocate |
|
48 |
Finds the location of the line |
|
49 |
Outputs positive for right side |
|
50 |
Negative for left, or NOLINE if a line is not found |
|
51 |
*/ |
|
64 | 52 |
int lineLocate(int* colors); |
65 | 53 |
|
66 |
/** updatebarCode
|
|
67 |
* Reads in and processes
|
|
68 |
* bar code data
|
|
69 |
*/
|
|
54 |
/* updatebarCode |
|
55 |
Reads in and processes |
|
56 |
bar code data |
|
57 |
*/ |
|
70 | 58 |
void updateBarCode(void); |
71 | 59 |
|
72 |
/** |
|
73 |
* @brief Gets the completed value read by the barcode reader, or NOBARCODE. |
|
74 |
* |
|
75 |
* Returns a bar code if available (if at the end of a barcode) and resets the |
|
76 |
* barcodePosition to 0. Otherwise, return NOBARCODE. * |
|
77 |
* @return The value of the barcode if a complete barcode, else NOBARCODE. |
|
78 |
*/ |
|
60 |
/* getBarCode |
|
61 |
returns a bar code, if |
|
62 |
available, otherwise NOBARCODE |
|
63 |
*/ |
|
79 | 64 |
int getBarCode(void); |
80 | 65 |
|
81 |
|
|
82 |
//! A simple function to return the minimum of two integers. |
|
66 |
/* min max |
|
67 |
returns the minimum/maximum of two values |
|
68 |
*/ |
|
83 | 69 |
int min(int x, int y); |
84 |
//! A simple function to return the maximum of two integers. |
|
85 | 70 |
int max(int x, int y); |
86 | 71 |
|
87 |
/** @todo Alex: I hate these functions, but I'm keeping them so code will still work. But we should delete them sometime. */ |
|
88 |
|
|
89 |
/** motorLeft |
|
90 |
* Commands the left motor |
|
91 |
* Cannot be used to stop |
|
92 |
* 0-126 are backward |
|
93 |
* 127-255 are forward |
|
94 |
*/ |
|
72 |
/* motorLeft |
|
73 |
Commands the left motor |
|
74 |
Cannot be used to stop |
|
75 |
0-126 are backward |
|
76 |
127-255 are forward |
|
77 |
*/ |
|
95 | 78 |
void motorLeft(int speed); |
96 | 79 |
|
97 |
/** motorRight
|
|
98 |
* Commands the right motor
|
|
99 |
* Cannot be used to stop
|
|
100 |
* 0-126 are backward
|
|
101 |
* 127-255 are forward
|
|
102 |
*/
|
|
80 |
/* motorRight |
|
81 |
Commands the right motor |
|
82 |
Cannot be used to stop |
|
83 |
0-126 are backward |
|
84 |
127-255 are forward |
|
85 |
*/ |
|
103 | 86 |
void motorRight(int speed); |
104 | 87 |
|
105 |
/** lost
|
|
106 |
* Internal counter to detect if the line was lost
|
|
107 |
*/
|
|
88 |
/* lost |
|
89 |
Internal counter to detect if the line was lost |
|
90 |
*/ |
|
108 | 91 |
int lost; |
109 | 92 |
|
110 |
int onLine(void); |
|
111 |
|
|
112 | 93 |
#endif |
trunk/code/projects/linefollowing/lineDrive.c | ||
---|---|---|
146 | 146 |
int turn(int type, int dir) |
147 | 147 |
{ |
148 | 148 |
if(stateLength!=0)return ERROR; |
149 |
if(dir==IRIGHT) |
|
150 |
{ |
|
151 |
stateLength++; |
|
152 |
state[1]=IRIGHT; |
|
153 |
return NORMAL; |
|
154 |
} |
|
155 |
if(dir==IUTURN) |
|
156 |
{ |
|
157 |
stateLength+=2; |
|
158 |
state[1]=state[2]=ILEFT; |
|
159 |
return NORMAL; |
|
160 |
} |
|
161 |
if(dir==ISTRAIGHT && type==SINGLE) |
|
162 |
{ |
|
163 |
stateLength++; |
|
164 |
state[1]=ISTRAIGHT; |
|
165 |
return NORMAL; |
|
166 |
} |
|
167 |
if(dir==ISTRAIGHT) |
|
168 |
{ |
|
169 |
stateLength+=2; |
|
170 |
state[1]=state[2]=ISTRAIGHT; |
|
171 |
return NORMAL; |
|
172 |
} |
|
173 |
// At this point, must be left turn |
|
174 |
if(type==SINGLE) |
|
175 |
{ |
|
176 |
stateLength++; |
|
177 |
state[1]=ILEFT; |
|
178 |
return NORMAL; |
|
179 |
} |
|
180 |
if(type==DOUBLE_C || type==DOUBLE_T) |
|
181 |
{ |
|
182 |
stateLength+=3; |
|
183 |
state[1]=state[3]=ISTRAIGHT; |
|
184 |
state[2]=ILEFT; |
|
185 |
return NORMAL; |
|
186 |
} |
|
187 |
if(type==ON_RAMP) |
|
188 |
{ |
|
189 |
stateLength+=2; |
|
190 |
state[1]=ILEFT; |
|
191 |
state[2]=ISTRAIGHT; |
|
192 |
return NORMAL; |
|
193 |
} |
|
194 |
if(type==OFF_RAMP) |
|
195 |
{ |
|
196 |
stateLength+=2; |
|
197 |
state[1]=ISTRAIGHT; |
|
198 |
state[2]=ILEFT; |
|
199 |
return NORMAL; |
|
200 |
} |
|
149 |
if(dir==IRIGHT){stateLength++; state[1]=IRIGHT; return NORMAL;} |
|
150 |
if(dir==IUTURN){stateLength+=2; state[1]=state[2]=ILEFT; return NORMAL;} |
|
151 |
if(dir==ISTRAIGHT && type==SINGLE){stateLength++; state[1]=ISTRAIGHT; return NORMAL;} |
|
152 |
if(dir==ISTRAIGHT){stateLength+=2; state[1]=state[2]=ISTRAIGHT; return NORMAL;} |
|
153 |
//must be left turn |
|
154 |
if(type==SINGLE){stateLength++; state[1]=ILEFT; return NORMAL;} |
|
155 |
if(type==DOUBLE){stateLength+=3;state[1]=state[3]=ISTRAIGHT; state[2]=ILEFT; return NORMAL;} |
|
156 |
if(type==ON_RAMP){stateLength+=2; state[1]=ILEFT; state[2]=ISTRAIGHT; return NORMAL;} |
|
157 |
if(type==OFF_RAMP){stateLength+=2; state[1]=ISTRAIGHT; state[2]=ILEFT; return NORMAL;} |
|
201 | 158 |
|
202 | 159 |
//Should never get here |
203 | 160 |
return ERROR; |
trunk/code/projects/linefollowing/main.c | ||
---|---|---|
2 | 2 |
#include <lineFollow.h> |
3 | 3 |
|
4 | 4 |
|
5 |
|
|
5 | 6 |
int main(void) |
6 | 7 |
{ |
7 | 8 |
|
... | ... | |
12 | 13 |
while(1) |
13 | 14 |
{ |
14 | 15 |
|
16 |
|
|
17 |
for(int i=0; i<8; i++){ |
|
18 |
usb_puti(read_line(i)); |
|
19 |
usb_putc('\t'); |
|
20 |
} |
|
21 |
usb_putc(13); |
|
22 |
|
|
23 |
/* |
|
24 |
|
|
15 | 25 |
for(int q=0; q<500; q++) |
16 | 26 |
barCode = lineFollow(200); |
17 | 27 |
while(mergeLeft()); |
18 |
for(int q=0; q<1000; q++) |
|
19 |
lineFollow(200); |
|
28 |
for(int q=0; q<1000; q++)lineFollow(200); |
|
20 | 29 |
|
21 | 30 |
continue; |
22 |
|
|
23 |
if(barCode==-25) |
|
24 |
while(turnRight()); |
|
25 |
|
|
31 |
if(barCode==-25)while(turnRight()); |
|
26 | 32 |
continue; |
27 |
|
|
28 | 33 |
if(barCode != -2 && barCode != LINELOST) |
29 | 34 |
{ |
30 | 35 |
usb_puti(barCode); |
31 | 36 |
usb_putc('\n'); |
32 | 37 |
} |
38 |
*/ |
|
39 |
|
|
40 |
|
|
41 |
|
|
33 | 42 |
/* |
34 | 43 |
|
35 | 44 |
switch (barCode) |
... | ... | |
65 | 74 |
} |
66 | 75 |
return 0; |
67 | 76 |
} |
68 |
|
|
69 | 77 |
void right() |
70 | 78 |
{ |
71 | 79 |
motor_r_set(BACKWARD, 200); |
... | ... | |
73 | 81 |
delay_ms(400); |
74 | 82 |
} |
75 | 83 |
|
84 |
|
|
76 | 85 |
void straight() |
77 | 86 |
{ |
78 | 87 |
motor_r_set(FORWARD, 210); |
trunk/code/projects/linefollowing/lineDrive.h | ||
---|---|---|
3 | 3 |
|
4 | 4 |
#include "lineFollow.h" |
5 | 5 |
|
6 |
/* Old definitions, delete as soon as possible |
|
7 |
#define DOUBLE 0 |
|
6 |
#define DOUBLE 0 |
|
8 | 7 |
#define SINGLE 1 |
9 | 8 |
#define ON_RAMP 2 |
10 | 9 |
#define OFF_RAMP 3 |
11 |
*/ |
|
12 | 10 |
|
13 |
#define SINGLE 0 |
|
14 |
#define ON_RAMP 1 |
|
15 |
#define OFF_RAMP 2 |
|
16 |
#define DOUBLE_C 3 |
|
17 |
#define DOUBLE_T 4 |
|
18 |
|
|
19 | 11 |
#define ISTRAIGHT 0 |
20 | 12 |
#define ILEFT 1 |
21 | 13 |
#define IRIGHT 2 |
trunk/code/projects/linefollowing/lineFollow.c | ||
---|---|---|
1 | 1 |
/** |
2 | 2 |
* @file lineFollow.c |
3 |
* @defgroup lineFollwing Line Following |
|
4 | 3 |
* |
5 | 4 |
* Takes care of following a line. Running this program is done by calling the |
6 | 5 |
* init() function and then the lineFollow(speed) command. However, direct use |
7 | 6 |
* of this class is discouraged as its behavior is used by lineDrive.c, which |
8 | 7 |
* extends this class to provide behavior functionality. |
9 | 8 |
* |
10 |
* @author Dan Jacobs and the Colony Project
|
|
9 |
* @author Dan Jacobs |
|
11 | 10 |
* @date 11-1-2010 |
12 | 11 |
*/ |
13 | 12 |
|
14 | 13 |
#include "lineFollow.h" |
15 | 14 |
|
16 |
//! The number of bits expected in a barcode |
|
17 | 15 |
#define CODESIZE 5 |
18 | 16 |
|
19 | 17 |
int countHi = 0; |
... | ... | |
23 | 21 |
int barCodePosition=0; |
24 | 22 |
|
25 | 23 |
int turnDistance=0; |
26 |
//! Counts the number of full line readings before we determine an intersection |
|
27 | 24 |
int intersectionFilter=0; |
28 | 25 |
int disableBarCode=0; |
29 | 26 |
|
30 |
//! Keeps track of where the encoder of one motor started, for use in turns. |
|
31 |
int encoderStart = -1; |
|
32 |
int encoderReset = 0; // 0 if encoderStart has no value set |
|
33 | 27 |
|
34 |
|
|
28 |
/** |
|
29 |
* Initializes line following. Must be called before other line-following |
|
30 |
* behavior will work. |
|
31 |
*/ |
|
35 | 32 |
void lineFollow_init() |
36 | 33 |
{ |
37 | 34 |
analog_init(0); |
... | ... | |
57 | 54 |
//not on line |
58 | 55 |
if(position == NOLINE) |
59 | 56 |
{ |
60 |
if(lost++ > 20)
|
|
57 |
if(lost++>20)
|
|
61 | 58 |
{ |
62 | 59 |
orb2_set_color(GREEN); |
63 | 60 |
motors_off(); |
... | ... | |
66 | 63 |
} |
67 | 64 |
else if(position == FULL_LINE) |
68 | 65 |
{ |
69 |
if(intersectionFilter++ > 4)
|
|
66 |
if(intersectionFilter++>4)
|
|
70 | 67 |
{ |
71 | 68 |
orb2_set_color(RED); |
72 | 69 |
barCodePosition=0; |
... | ... | |
156 | 153 |
/** |
157 | 154 |
* Turns left at a cross of two lines. Assumes that we are at lines in a cross |
158 | 155 |
* pattern, and turns until it sets straight on the new line. |
159 |
* @return 0 if turn finishes otherwise return 1
|
|
156 |
* @return 1 if the turn was executed successfully, 0 otherwise.
|
|
160 | 157 |
*/ |
161 | 158 |
int turnLeft() |
162 | 159 |
{ |
163 |
/*motor_l_set(BACKWARD, 200);
|
|
160 |
motor_l_set(BACKWARD, 200); |
|
164 | 161 |
motor_r_set(FORWARD, 200); |
165 | 162 |
int colors[5]; |
166 | 163 |
updateLine(colors); |
... | ... | |
174 | 171 |
return 0; |
175 | 172 |
} |
176 | 173 |
} |
177 |
return 1;*/ |
|
178 |
|
|
179 |
motor_l_set(BACKWARD,200); |
|
180 |
motor_r_set(FORWARD,200); |
|
181 |
if(!encoderReset) |
|
182 |
{ |
|
183 |
encoderStart = encoder_get_x(RIGHT); |
|
184 |
encoderReset = 1; |
|
185 |
} |
|
186 |
|
|
187 |
if(encoder_get_x(RIGHT) < encoderStart) |
|
188 |
{ |
|
189 |
encoderStart = 0; |
|
190 |
// Temporary: display an "error message" in case of overflow. |
|
191 |
// Using this for debugging, take it out soon! |
|
192 |
motor_l_set(FORWARD,0); |
|
193 |
motor_r_set(FORWARD,0); |
|
194 |
orb_set_color(WHITE); |
|
195 |
delay_ms(2000); |
|
196 |
} |
|
197 |
|
|
198 |
if(encoder_get_x(RIGHT) - encoderStart > 300) |
|
199 |
{ |
|
200 |
encoderReset = 0; |
|
201 |
return 0; |
|
202 |
} |
|
203 | 174 |
return 1; |
204 | 175 |
} |
205 | 176 |
|
... | ... | |
208 | 179 |
/** |
209 | 180 |
* Turns right at a cross of two lines. Assumes that we are at lines in a cross |
210 | 181 |
* pattern, and turns until it sets straight on the new line. |
211 |
* @return 0 if the turn finishes otherwise return 1
|
|
182 |
* @return 1 if the turn was executed successfully, 0 otherwise.
|
|
212 | 183 |
*/ |
213 | 184 |
int turnRight() |
214 | 185 |
{ |
... | ... | |
231 | 202 |
|
232 | 203 |
|
233 | 204 |
|
205 |
|
|
234 | 206 |
int getBarCode() |
235 | 207 |
{ |
236 | 208 |
if(barCodePosition!=CODESIZE) return NOBARCODE ; |
237 | 209 |
int temp = 0; |
238 |
for(int i=0; i<CODESIZE; i++) |
|
210 |
int i; |
|
211 |
for(i=0; i<CODESIZE; i++) |
|
239 | 212 |
temp += (barCode[i] << i); |
240 | 213 |
barCodePosition = 0; |
241 | 214 |
return temp; |
... | ... | |
267 | 240 |
return NOLINE; |
268 | 241 |
if(count==5) |
269 | 242 |
return FULL_LINE; |
270 |
return (wsum/count)-4; // Subtract 4 to center the index around the center.
|
|
243 |
return (wsum/count)-4; |
|
271 | 244 |
} |
272 | 245 |
|
273 | 246 |
|
274 | 247 |
void updateBarCode() |
275 | 248 |
{ |
276 |
//! Note: currently only uses one of the barcode sensors. |
|
277 | 249 |
|
250 |
//NOTE: currently only uses one of the barcode sensors. |
|
251 |
|
|
278 | 252 |
//maps the sensors to the analog input ports |
279 | 253 |
int ports[2] = {8,1}; |
280 | 254 |
int current[2]; |
... | ... | |
310 | 284 |
} |
311 | 285 |
|
312 | 286 |
|
287 |
//! A simple function to return the minimum of two integers. |
|
313 | 288 |
int min(int x, int y){return x>y ? y : x;} |
289 |
//! A simple function to return the maximum of two integers. |
|
314 | 290 |
int max(int x, int y){return x<y ? y : x;} |
315 | 291 |
|
316 | 292 |
void motorLeft(int speed){ |
trunk/code/projects/linefollowing/Makefile | ||
---|---|---|
1 |
#this is a local makefile |
|
1 |
# this is a local makefile
|
|
2 | 2 |
|
3 | 3 |
# Relative path to the root directory (containing lib directory) |
4 | 4 |
ifndef COLONYROOT |
... | ... | |
11 | 11 |
USE_WIRELESS = 1 |
12 | 12 |
|
13 | 13 |
# com1 = serial port. Use lpt1 to connect to parallel port. |
14 |
AVRDUDE_PORT = $(shell if uname -s |grep -i w32 >/dev/null; then echo 'COM4:'; else echo '/dev/ttyUSB*'; fi)
|
|
14 |
AVRDUDE_PORT = $(shell if uname -s |grep -i w32 >/dev/null; then echo 'COM4:'; else echo '/dev/ttyUSB0'; fi)
|
|
15 | 15 |
|
16 | 16 |
else |
17 | 17 |
COLONYROOT := ../$(COLONYROOT) |
trunk/code/projects/libdragonfly/analog.c | ||
---|---|---|
101 | 101 |
|
102 | 102 |
// Set external mux lines to outputs |
103 | 103 |
DDRG |= 0x1C; |
104 |
|
|
104 |
|
|
105 |
// Set line sensor mux lines to output. Uses LCD/SPI header |
|
106 |
DDRD |=0xE0; |
|
107 |
|
|
105 | 108 |
// Set up first port for conversions |
106 | 109 |
set_adc_mux(0x00); |
107 | 110 |
adc_current_port = AN1; |
108 | 111 |
|
112 |
//Start the conversion loop if requested |
|
113 |
if (start_conversion) |
|
114 |
analog_start_loop(); |
|
109 | 115 |
|
110 | 116 |
//Conversion loop disabled by default |
111 | 117 |
} |
... | ... | |
287 | 293 |
return ((adc_h << 2) | (adc_l >> 6)); |
288 | 294 |
} |
289 | 295 |
|
296 |
|
|
297 |
/** Returns the 10 bit value from the line sensors **/ |
|
298 |
unsigned int read_line(int which) { |
|
299 |
int adc_h; |
|
300 |
int adc_l; |
|
301 |
|
|
302 |
// Let any previous conversion finish |
|
303 |
while (ADCSRA & _BV(ADSC)); |
|
304 |
|
|
305 |
ADMUX = ADMUX_OPT + AN1; |
|
306 |
|
|
307 |
// which = (which&1)<<2 + (which&2) + (which&4)>>2; |
|
308 |
|
|
309 |
// mask so only proper bits are possible. |
|
310 |
PORTD = (PORTD & 0x1F) | ((which & 0x07) << 5); |
|
311 |
// Start the conversion |
|
312 |
ADCSRA |= _BV(ADSC); |
|
313 |
|
|
314 |
// Wait for the conversion to finish |
|
315 |
while (ADCSRA & _BV(ADSC)); |
|
316 |
|
|
317 |
adc_l = ADCL; |
|
318 |
adc_h = ADCH; |
|
319 |
|
|
320 |
return ((adc_h << 2) | (adc_l >> 6)); |
|
321 |
|
|
322 |
} |
|
323 |
|
|
324 |
|
|
325 |
|
|
326 |
|
|
290 | 327 |
/** |
291 | 328 |
* Returns the current position of the wheel, as an integer |
292 | 329 |
* in the range 0 - 255. |
... | ... | |
322 | 359 |
} |
323 | 360 |
|
324 | 361 |
/**@}**/ //end defgroup |
362 |
|
|
363 |
|
|
364 |
ISR(ADC_vect) { |
|
365 |
int adc_h = 0; |
|
366 |
int adc_l = 0; |
|
367 |
|
|
368 |
if(adc_loop_status != ADC_LOOP_RUNNING) return; |
|
369 |
|
|
370 |
//Store the value only if this read isn't for the BOM |
|
371 |
if (ADMUX != BOM_PORT) { |
|
372 |
adc_l = ADCL; |
|
373 |
adc_h = ADCH; |
|
374 |
|
|
375 |
an_val[adc_current_port - 1].adc10 = (adc_h << 2) | (adc_l >> 6); |
|
376 |
an_val[adc_current_port - 1].adc8 = adc_h; |
|
377 |
} |
|
378 |
|
|
379 |
//Skip AN7 because it is not a real port |
|
380 |
if (adc_current_port == AN6) { |
|
381 |
ADMUX = ADMUX_OPT | EXT_MUX; |
|
382 |
set_adc_mux(AN8 - 8); |
|
383 |
adc_current_port = AN8; |
|
384 |
//Wrap around |
|
385 |
} else if (adc_current_port == AN11) { |
|
386 |
adc_current_port = AN1; |
|
387 |
ADMUX = ADMUX_OPT | adc_current_port; |
|
388 |
//Normal increment |
|
389 |
} else { |
|
390 |
adc_current_port++; |
|
391 |
|
|
392 |
if(adc_current_port < EXT_MUX) { |
|
393 |
ADMUX = ADMUX_OPT | adc_current_port; |
|
394 |
} else { |
|
395 |
ADMUX = ADMUX_OPT | EXT_MUX; |
|
396 |
set_adc_mux(adc_current_port - 8); |
|
397 |
} |
|
398 |
} |
|
399 |
|
|
400 |
//Stop loop if signal is set |
|
401 |
if(adc_sig_stop_loop) { |
|
402 |
adc_sig_stop_loop = 0; |
|
403 |
adc_loop_status = ADC_LOOP_STOPPED; |
|
404 |
return; |
|
405 |
} |
|
406 |
|
|
407 |
//Start next conversion |
|
408 |
ADCSRA |= _BV(ADSC); |
|
409 |
} |
|
410 |
|
Also available in: Unified diff