Project

General

Profile

Revision 9143e077

ID9143e077022d223673b8e8afa2d6a6a512495c41

Added by Lalitha Ganesan over 12 years ago

lineFollow functions for Scout.

View differences:

scout/libscout/src/behaviors/lineFollow.cpp
1
/**
2
 * @file lineFollow.cpp
3
 * @defgroup lineFollwing Line Following
4
 *
5
 * Takes care of following a line. Running this program is done by calling the
6
 * init() function and then the lineFollow(speed) command.  However, direct use
7
 * of this class is discouraged as its behavior is used by lineDrive.cpp, which
8
 * extends this class to provide behavior functionality.
9
 *
10
 * @author Dan Jacobs and the Colony Project
11
 * @date 11-1-2010
12
 */
13

  
14
#include "lineFollow.h"
15

  
16
/**
17
 * Helps with debugging.
18
 * 0 - no debug output.
19
 * 1 - print out buckets
20
 * 2 - print out line sensor readings
21
 */
22
#define DBG_LINEFOLLOW 2
23

  
24
//! Anything lower than this value is white
25
int GREY_THRESHOLD = 300;
26
//! Anything higher than this value is black
27
int BLACK_THRESHOLD = 750;
28

  
29
int countHi = 0;
30
int countLo = 0;
31
int maxAvg, avg;
32

  
33
int duration[2] = {0};
34
int lastColor[2] = {0};
35
char isReset[2] = {1};
36
int lastReadings[2][ NUM_READINGS ] = {{0}};
37
int lastReadingsPtr[2] = {0};
38
int numLast[2][4] = { {0, 0, 0, NUM_READINGS}, {0, 0, 0, NUM_READINGS} };
39
int bitColor[2] = {0};
40

  
41
int turnDistance=0;
42
//! Counts the number of full line readings before we determine an intersection
43
int intersectionFilter=0;
44

  
45
//! Keeps track of where the encoder of one motor started, for use in turns.
46
int encoderStart = -1;
47
int encoderReset = 0;   // 0 if encoderStart has no value set
48

  
49

  
50
void lineFollow::init()
51
{
52
    int i, j, curReading;
53
    int lowGrey = 1000, highGrey = 0, lowBlack = 1000,
54
        highBlack = 0;
55

  
56
	analog_init(0);
57
    encoders_init();
58
	lost = 0;
59
	intersectionFilter=0;
60

  
61
    for(i=0; i<2; i++)
62
    {
63
        for(j=0; j<NUM_READINGS; j++)
64
        {
65
            lastReadings[i][j] = BAD_READING;
66
        }
67
        isReset[i] = 1;
68
    }
69
    
70
    // Calibrate thresholds
71
    orb_set_color(YELLOW);
72
    delay_ms(2000);
73

  
74
    orb_set_color(BLUE);
75

  
76
    for(i=0; i<100; i++)
77
    {
78
        curReading = read_line(LEFT_SENSOR + 6);
79
        if(curReading < lowGrey)
80
            lowGrey = curReading;
81
        if(curReading > highGrey)
82
            highGrey = curReading;
83

  
84
        delay_ms(20);
85
    }
86

  
87
    orb_set_color(YELLOW);
88
    delay_ms(2000);
89

  
90
    orb_set_color(GREEN);
91

  
92
    for(i=0; i<100; i++)
93
    {
94
        curReading = read_line(LEFT_SENSOR + 6);
95
        if(curReading < lowBlack)
96
            lowBlack = curReading;
97
        if(curReading > highBlack)
98
            highBlack = curReading;
99

  
100
        delay_ms(20);
101
    }
102

  
103
    orbs_set(0,0,0,0,0,0);
104

  
105
    GREY_THRESHOLD = lowGrey / 2;
106
    BLACK_THRESHOLD = (highGrey + lowBlack) / 2;
107

  
108
    usb_puts("Grey: ");
109
    usb_puti(lowGrey);
110
    usb_puts(", ");
111
    usb_puti(highGrey);
112
    usb_puts("\nBlack: ");
113
    usb_puti(lowBlack);
114
    usb_puts(", ");
115
    usb_puti(highBlack);
116
    usb_puts("\nThresholds: ");
117
    usb_puti(GREY_THRESHOLD);
118
    usb_puts(", ");
119
    usb_puti(BLACK_THRESHOLD);
120
    usb_puts("\n\n");
121

  
122
    delay_ms(1500);
123
}
124

  
125

  
126
/** 
127
 * Follows a line at the given speed.
128
 * @param speed The speed with which to follow the line.
129
 */
130
int lineFollow(int speed)
131
{
132
	int colors[5];
133
	int position;
134
	
135

  
136
	updateLine(colors);
137
	position = lineLocate(colors); 	
138
	
139
	//not on line
140
	if(position == NOLINE)
141
	{
142
		if(lost++ > 20)
143
		{
144
			orb2_set_color(GREEN);
145
			motors_off();
146
			return LINELOST;
147
		}
148
	}
149
	else if(position == FULL_LINE)
150
	{
151
		if(intersectionFilter++ > 4)
152
		{
153
			orb2_set_color(RED);
154
			barCodePosition[0]=0;
155
            barCodePosition[1]=0;
156
			disableBarCode=50;
157
		}
158
	}
159
	//on line
160
	else
161
	{
162
		position*=30;
163
		orb2_set_color(ORB_OFF);
164
		motorLeft(min(speed+position, 255));
165
		motorRight(min(speed-position, 255));
166
		lost=0;
167
		intersectionFilter=0;
168
	}
169
}
170

  
171

  
172
/**
173
 * Turns left at a cross of two lines.  Assumes that we are at lines in a cross
174
 * pattern, and turns until it sets straight on the new line.
175
 * @return 0 if turn finishes otherwise return 1
176
 */
177
int turnLeft()
178
{
179
        motors->set_sides(-20, 20, MOTOR_ABSOLUTE);
180
		
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
            motors->set_sides(0, 0, MOTOR_ABSOLUTE);
191
            delay_ms(2000);
192
        }
193

  
194
        if(encoder_get_x(RIGHT) - encoderStart > 300)
195
        {
196
            encoderReset = 0;
197
            return 0;
198
        }
199
        return 1;
200
}
201

  
202

  
203

  
204
/**
205
 * Turns right at a cross of two lines.  Assumes that we are at lines in a cross
206
 * pattern, and turns until it sets straight on the new line.
207
 * @return 0 if the turn finishes otherwise return 1
208
 */
209
int lineFollow::turnRight()
210
{
211
		/// Set motors using new motors functions
212
        /// motor_r_set(BACKWARD, 200);
213
        /// motor_l_set(FORWARD, 200);
214
        
215
		int colors[5];
216
        updateLine(colors);
217
        int position = lineLocate(colors);
218
        if(position>2 || position<-2)turnDistance++;
219
        if(turnDistance>1) 
220
	{
221
		if(position<3 && position>-3)
222
		{
223
			turnDistance = 0;
224
			 return 0;
225
		}
226
	}
227
	return 1;
228
}
229

  
230

  
231
void updateLine(int* values)
232
{	
233
	for(int i = 0; i<5; i++)
234
		values[i] = (read_line(4-i) < LINE_COLOR ? LWHITE : LBLACK);
235
}
236

  
237

  
238
int lineLocate(int* colors)
239
{
240
	int i;
241
	int wsum = 0;
242
	int count=0;
243

  
244
	for(i = 0; i<5; i++)
245
	{
246
		count += colors[i]/2;
247
		wsum += (i)*colors[i];
248
	}
249
	if(count==0)
250
		return NOLINE;	
251
	if(count==5)
252
		return FULL_LINE;
253
	return (wsum/count)-4; /// Subtract 4 to center the index around the center.
254
}
255

  
256
void printBuckets(int i)
257
{
258
    int j;
259

  
260
    usb_puts("LP[");
261
    usb_puti(i);
262
    usb_puts("]: ");
263
    usb_puti(lastReadingsPtr[i]);
264
    usb_puts(", Totals: ");
265

  
266
    for(int j=0; j<=3; j++)
267
    {
268
        usb_puts("[");
269
        usb_puti(j);
270
        usb_puts("]: ");
271
        usb_puti(numLast[i][j]);
272
        usb_puts(" ");
273
    }
274
    usb_puts("\t ");
275
    usb_puts("\n");
276
}
277

  
278
void addToBuckets(int curColor, int i)
279
{
280
    int oldest = lastReadings[i][lastReadingsPtr[i]];
281
    numLast[i][oldest]--;
282
    lastReadings[i][lastReadingsPtr[i]] = curColor;
283
    lastReadingsPtr[i] = (lastReadingsPtr[i]+1) % NUM_READINGS;
284
    numLast[i][curColor]++;
285

  
286
    if(DBG_LINEFOLLOW == 1)
287
    {
288
        printBuckets(i);
289
    }
290
}
291

  
292

  
293
int min(int x, int y){return x>y ? y : x;}
294
int max(int x, int y){return x<y ? y : x;}
295

  
296
void motorLeft(int speed)
297
{
298
	int tempspeed = 0;
299
	if ((speed-=127)>=0)
300
	{	
301
		tempspeed = 160+speed*95/128;
302
		motors->set_sides(tempspeed, 0, MOTOR_ABSOLUTE);
303
	}
304
	else
305
	{
306
		tempspeed = 160+speed*95/128;
307
		motors->set_sides(-tempspeed, 0, MOTOR_ABSOLUTE);
308
	}
309
}
310

  
311
void motorRight(int speed)
312
{
313
	int tempspeed = 0;
314
	if ((speed-=127)>=0)
315
	{	
316
		tempspeed = 160+speed*95/128;
317
		motors->set_sides(0, tempspeed, MOTOR_ABSOLUTE);
318
	}
319
	else
320
	{
321
		tempspeed = 160+speed*95/128;
322
		motors->set_sides(0, -tempspeed, MOTOR_ABSOLUTE);
323
	}
324
}
325
	
scout/libscout/src/behaviors/lineFollow.h
1

  
2
#ifndef _LINEFOLLOW_H_
3
#define _LINEFOLLOW_H_
4

  
5
#include "../Behavior.h"
6

  
7
#define LWHITE			0
8
#define LGREY			1
9
#define LBLACK	 		2
10
#define BAD_READING     3
11
#define CENTER			3
12
#define LINELOST		-1
13

  
14
#define INTERSECTION 	-25
15

  
16
#define NOLINE			-50
17
#define FULL_LINE 		-51
18

  
19
#define NUM_READINGS 20
20

  
21
#define LEFT_SENSOR     1
22
#define RIGHT_SENSOR    0
23

  
24
class lineFollow : Behavior
25
{
26
	public:
27
		lineFollow(std::string scoutname) : Behavior(scoutname) {};
28
        /** Actually executes the behavior. */
29
		void init();
30
};
31

  
32
/**	lineFollow
33
 *	Must call lineFollow_init first
34
 *	Must be called inside a loop
35
 */
36
int lineFollow(int speed);
37

  
38
/**	turnLeft turnRight
39
 *	Must be called inside a loop
40
 *	returns 0 when complete
41
 */
42
int turnLeft(void);
43
int turnRight(void);
44

  
45
void addToBuckets(int curColor, int i);
46
void printBuckets();
47

  
48
/**
49
 * @brief Updates the values stored in the array to white or black based on
50
 * current sensor readings.
51
 *
52
 * @param values The array of five integers to be updated. 
53
 */
54
void updateLine(int* values); 
55

  
56
/**
57
 * @brief Returns an index of the middle of the line based on line readings.
58
 *
59
 * Two special return values are possible:
60
 *   NOLINE if none of the sensors holds a black value, and
61
 *   FULL_LINE if all of the sensors see black.
62
 *
63
 * Otherwise, returns a value from -4 (farthest left) to 4 (farthest right), with
64
 * 0 the line being centered in the middle.
65
 *
66
 * @param colors The array of 5 readings from the line sensor.  Must be either
67
 *    LWHITE or LBLACK.
68
 * @return Either a special value or an index from -4 to 4.
69
 *
70
 */
71
int lineLocate(int* colors);
72

  
73

  
74
//! A simple function to return the minimum of two integers.
75
int min(int x, int y);
76
//! A simple function to return the maximum of two integers.
77
int max(int x, int y);
78

  
79
/** @todo Alex: I hate these functions, but I'm keeping them so code will still work. But we should delete them sometime. */
80

  
81
/**	motorLeft
82
 *	Commands the left motor
83
 *	Cannot be used to stop
84
 *	0-126 are backward
85
 *	127-255 are forward
86
 */
87
void motorLeft(int speed);
88

  
89
/**	motorRight
90
 *	Commands the right motor
91
 *	Cannot be used to stop
92
 *	0-126 are backward
93
 *	127-255 are forward
94
 */
95
void motorRight(int speed);
96

  
97
/**	lost
98
 *	Internal counter to detect if the line was lost
99
 */
100
int lost;
101

  
102
int onLine(void);
103

  
104
#endif

Also available in: Unified diff