-
Notifications
You must be signed in to change notification settings - Fork 1
/
Copy pathWhite_Line_Following.c
306 lines (250 loc) · 9.29 KB
/
White_Line_Following.c
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
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
/************************************************************************************
This experiment demonstrates the application of a simple line follower robot. The
robot follows a white line over a black backround
Concepts covered: ADC, LCD interfacing, motion control based on sensor data
LCD Connections:
LCD Microcontroller Pins
RS --> PC0
RW --> PC1
EN --> PC2
DB7 --> PC7
DB6 --> PC6
DB5 --> PC5
DB4 --> PC4
ADC Connection:
ACD CH. PORT Sensor
0 PF0 Battery Voltage
1 PF1 White line sensor 3
2 PF2 White line sensor 2
3 PF3 White line sensor 1
4 PF4 IR Proximity analog sensor 1*****
5 PF5 IR Proximity analog sensor 2*****
6 PF6 IR Proximity analog sensor 3*****
7 PF7 IR Proximity analog sensor 4*****
8 PK0 IR Proximity analog sensor 5
9 PK1 Sharp IR range sensor 1
10 PK2 Sharp IR range sensor 2
11 PK3 Sharp IR range sensor 3
12 PK4 Sharp IR range sensor 4
13 PK5 Sharp IR range sensor 5
14 PK6 Servo Pod 1
15 PK7 Servo Pod 2
***** For using Analog IR proximity (1, 2, 3 and 4) sensors short the jumper J2.
To use JTAG via expansion slot of the microcontroller socket remove these jumpers.
Motion control Connection:
L-1---->PA0; L-2---->PA1;
R-1---->PA2; R-2---->PA3;
PL3 (OC5A) ----> PWM left; PL4 (OC5B) ----> PWM right;
LCD Display interpretation:
****************************************************************************
*LEFT WL SENSOR CENTER WL SENSOR RIGHT WL SENSOR BLANK *
*BLANK BLANK BLANK BLANK *
****************************************************************************
Note:
1. Make sure that in the configuration options following settings are
done for proper operation of the code
Microcontroller: atmega2560
Frequency: 14745600
Optimization: -O0 (For more information read section: Selecting proper optimization
options below figure 2.22 in the Software Manual)
2. Make sure that you copy the lcd.c file in your folder
3. Distance calculation is for Sharp GP2D12 (10cm-80cm) IR Range sensor
*********************************************************************************/
/********************************************************************************
Copyright (c) 2010, NEX Robotics Pvt. Ltd. -*- c -*-
All rights reserved.
Redistribution and use in source and binary forms, with or without
modification, are permitted provided that the following conditions are met:
* Redistributions of source code must retain the above copyright
notice, this list of conditions and the following disclaimer.
* Redistributions in binary form must reproduce the above copyright
notice, this list of conditions and the following disclaimer in
the documentation and/or other materials provided with the
distribution.
* Neither the name of the copyright holders nor the names of
contributors may be used to endorse or promote products derived
from this software without specific prior written permission.
* Source code can be used for academic purpose.
For commercial use permission form the author needs to be taken.
THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
POSSIBILITY OF SUCH DAMAGE.
Software released under Creative Commence cc by-nc-sa licence.
For legal information refer to:
http://creativecommons.org/licenses/by-nc-sa/3.0/legalcode
********************************************************************************/
#include <avr/io.h>
#include <avr/interrupt.h>
#include <util/delay.h>
#include <math.h> //included to support power function
#include "lcd.c"
void port_init();
void timer5_init();
void velocity(unsigned char, unsigned char);
void motors_delay();
unsigned char ADC_Conversion(unsigned char);
unsigned char ADC_Value;
unsigned char flag = 0;
unsigned char Left_white_line = 0;
unsigned char Center_white_line = 0;
unsigned char Right_white_line = 0;
//Function to configure LCD port
void lcd_port_config (void)
{
DDRC = DDRC | 0xF7; //all the LCD pin's direction set as output
PORTC = PORTC & 0x80; // all the LCD pins are set to logic 0 except PORTC 7
}
//ADC pin configuration
void adc_pin_config (void)
{
DDRF = 0x00;
PORTF = 0x00;
DDRK = 0x00;
PORTK = 0x00;
}
//Function to configure ports to enable robot's motion
void motion_pin_config (void)
{
DDRA = DDRA | 0x0F;
PORTA = PORTA & 0xF0;
DDRL = DDRL | 0x18; //Setting PL3 and PL4 pins as output for PWM generation
PORTL = PORTL | 0x18; //PL3 and PL4 pins are for velocity control using PWM.
}
//Function to Initialize PORTS
void port_init()
{
lcd_port_config();
adc_pin_config();
motion_pin_config();
}
// Timer 5 initialized in PWM mode for velocity control
// Prescale:256
// PWM 8bit fast, TOP=0x00FF
// Timer Frequency:225.000Hz
void timer5_init()
{
TCCR5B = 0x00; //Stop
TCNT5H = 0xFF; //Counter higher 8-bit value to which OCR5xH value is compared with
TCNT5L = 0x01; //Counter lower 8-bit value to which OCR5xH value is compared with
OCR5AH = 0x00; //Output compare register high value for Left Motor
OCR5AL = 0xFF; //Output compare register low value for Left Motor
OCR5BH = 0x00; //Output compare register high value for Right Motor
OCR5BL = 0xFF; //Output compare register low value for Right Motor
OCR5CH = 0x00; //Output compare register high value for Motor C1
OCR5CL = 0xFF; //Output compare register low value for Motor C1
TCCR5A = 0xA9; /*{COM5A1=1, COM5A0=0; COM5B1=1, COM5B0=0; COM5C1=1 COM5C0=0}
For Overriding normal port functionality to OCRnA outputs.
{WGM51=0, WGM50=1} Along With WGM52 in TCCR5B for Selecting FAST PWM 8-bit Mode*/
TCCR5B = 0x0B; //WGM12=1; CS12=0, CS11=1, CS10=1 (Prescaler=64)
}
void adc_init()
{
ADCSRA = 0x00;
ADCSRB = 0x00; //MUX5 = 0
ADMUX = 0x20; //Vref=5V external --- ADLAR=1 --- MUX4:0 = 0000
ACSR = 0x80;
ADCSRA = 0x86; //ADEN=1 --- ADIE=1 --- ADPS2:0 = 1 1 0
}
//Function For ADC Conversion
unsigned char ADC_Conversion(unsigned char Ch)
{
unsigned char a;
if(Ch>7)
{
ADCSRB = 0x08;
}
Ch = Ch & 0x07;
ADMUX= 0x20| Ch;
ADCSRA = ADCSRA | 0x40; //Set start conversion bit
while((ADCSRA&0x10)==0); //Wait for conversion to complete
a=ADCH;
ADCSRA = ADCSRA|0x10; //clear ADIF (ADC Interrupt Flag) by writing 1 to it
ADCSRB = 0x00;
return a;
}
//Function To Print Sesor Values At Desired Row And Coloumn Location on LCD
void print_sensor(char row, char coloumn,unsigned char channel)
{
ADC_Value = ADC_Conversion(channel);
lcd_print(row, coloumn, ADC_Value, 3);
}
//Function for velocity control
void velocity (unsigned char left_motor, unsigned char right_motor)
{
OCR5AL = (unsigned char)left_motor;
OCR5BL = (unsigned char)right_motor;
}
//Function used for setting motor's direction
void motion_set (unsigned char Direction)
{
unsigned char PortARestore = 0;
Direction &= 0x0F; // removing upper nibbel for the protection
PortARestore = PORTA; // reading the PORTA original status
PortARestore &= 0xF0; // making lower direction nibbel to 0
PortARestore |= Direction; // adding lower nibbel for forward command and restoring the PORTA status
PORTA = PortARestore; // executing the command
}
void forward (void)
{
motion_set (0x06);
}
void stop (void)
{
motion_set (0x00);
}
void init_devices (void)
{
cli(); //Clears the global interrupts
port_init();
adc_init();
timer5_init();
sei(); //Enables the global interrupts
}
//Main Function
int main()
{
init_devices();
lcd_set_4bit();
lcd_init();
while(1)
{
Left_white_line = ADC_Conversion(3); //Getting data of Left WL Sensor
Center_white_line = ADC_Conversion(2); //Getting data of Center WL Sensor
Right_white_line = ADC_Conversion(1); //Getting data of Right WL Sensor
flag=0;
print_sensor(1,1,3); //Prints value of White Line Sensor1
print_sensor(1,5,2); //Prints Value of White Line Sensor2
print_sensor(1,9,1); //Prints Value of White Line Sensor3
if(Center_white_line<0x28)
{
flag=1;
forward();
velocity(150,150);
}
if((Left_white_line>0x28) && (flag==0))
{
flag=1;
forward();
velocity(130,50);
}
if((Right_white_line>0x28) && (flag==0))
{
flag=1;
forward();
velocity(50,130);
}
if(Center_white_line>0x28 && Left_white_line>0x28 && Right_white_line>0x28)
{
forward();
velocity(0,0);
}
}
}