/
Main.c
1551 lines (1193 loc) · 36.4 KB
/
Main.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
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
344
345
346
347
348
349
350
351
352
353
354
355
356
357
358
359
360
361
362
363
364
365
366
367
368
369
370
371
372
373
374
375
376
377
378
379
380
381
382
383
384
385
386
387
388
389
390
391
392
393
394
395
396
397
398
399
400
401
402
403
404
405
406
407
408
409
410
411
412
413
414
415
416
417
418
419
420
421
422
423
424
425
426
427
428
429
430
431
432
433
434
435
436
437
438
439
440
441
442
443
444
445
446
447
448
449
450
451
452
453
454
455
456
457
458
459
460
461
462
463
464
465
466
467
468
469
470
471
472
473
474
475
476
477
478
479
480
481
482
483
484
485
486
487
488
489
490
491
492
493
494
495
496
497
498
499
500
501
502
503
504
505
506
507
508
509
510
511
512
513
514
515
516
517
518
519
520
521
522
523
524
525
526
527
528
529
530
531
532
533
534
535
536
537
538
539
540
541
542
543
544
545
546
547
548
549
550
551
552
553
554
555
556
557
558
559
560
561
562
563
564
565
566
567
568
569
570
571
572
573
574
575
576
577
578
579
580
581
582
583
584
585
586
587
588
589
590
591
592
593
594
595
596
597
598
599
600
601
602
603
604
605
606
607
608
609
610
611
612
613
614
615
616
617
618
619
620
621
622
623
624
625
626
627
628
629
630
631
632
633
634
635
636
637
638
639
640
641
642
643
644
645
646
647
648
649
650
651
652
653
654
655
656
657
658
659
660
661
662
663
664
665
666
667
668
669
670
671
672
673
674
675
676
677
678
679
680
681
682
683
684
685
686
687
688
689
690
691
692
693
694
695
696
697
698
699
700
701
702
703
704
705
706
707
708
709
710
711
712
713
714
715
716
717
718
719
720
721
722
723
724
725
726
727
728
729
730
731
732
733
734
735
736
737
738
739
740
741
742
743
744
745
746
747
748
749
750
751
752
753
754
755
756
757
758
759
760
761
762
763
764
765
766
767
768
769
770
771
772
773
774
775
776
777
778
779
780
781
782
783
784
785
786
787
788
789
790
791
792
793
794
795
796
797
798
799
800
801
802
803
804
805
806
807
808
809
810
811
812
813
814
815
816
817
818
819
820
821
822
823
824
825
826
827
828
829
830
831
832
833
834
835
836
837
838
839
840
841
842
843
844
845
846
847
848
849
850
851
852
853
854
855
856
857
858
859
860
861
862
863
864
865
866
867
868
869
870
871
872
873
874
875
876
877
878
879
880
881
882
883
884
885
886
887
888
889
890
891
892
893
894
895
896
897
898
899
900
901
902
903
904
905
906
907
908
909
910
911
912
913
914
915
916
917
918
919
920
921
922
923
924
925
926
927
928
929
930
931
932
933
934
935
936
937
938
939
940
941
942
943
944
945
946
947
948
949
950
951
952
953
954
955
956
957
958
959
960
961
962
963
964
965
966
967
968
969
970
971
972
973
974
975
976
977
978
979
980
981
982
983
984
985
986
987
988
989
990
991
992
993
994
995
996
997
998
999
1000
#define F_CPU 14745600
#include <avr/io.h>
#include <avr/interrupt.h>
#include <util/delay.h>
//UART Globals
#define RX (1<<4)
#define TX (1<<3)
#define TE (1<<5)
#define RE (1<<7)
// flag for if reached at node
int ReachedNodeflag = 0;
//Variable to hold Character received from UART
volatile unsigned char Data;
volatile unsigned long int ShaftCountLeft = 0; //to keep track of left position encoder
volatile unsigned long int ShaftCountRight = 0; //to keep track of right position encoder
unsigned int Degrees; //to accept angle in degrees for turning
//Defining Thresholds
//Black line Threshold
#define THRESHOLD 47
//Black Node Threshold
#define THRESHOLDNODE 49
//Defining functions
void port_init();
void timer5_init();
void velocity(unsigned char, unsigned char);
unsigned char ADC_Conversion(unsigned char);
// Global variables
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 Name : magnet_pin_config
* Input : NONE
* Output : Register DDRH setting pin H0 as Output Port, Logic Low supplied to pin H0
* Logic : Masking of previous value of DDRH is done by bitwise 'or' operator with 0x01. This sets only Pin H0 as output Pin
* Masking of previous value of PORTH is done by bitwise 'and' operator with 0x01. Which sends logic LOW to H0
* Example call : magnet_pin_config()
*
*/
void magnet_pin_config()
{ //Setting H0 as output pin
DDRH = DDRH | 0x01 ;
//Magnet is set to be turned off initially by sending logic zero
PORTH = PORTH & 0xFE;
}
/*
* Function Name : magnet_on
* Input : NONE
* Output : Logic HIGH at Pin H0
* Logic : PORTH is assigned to 0x01 which makes Pin H0 to have a Logic HIGH
* Example call : magnet_on()
*
*/
void magnet_on()
{
PORTH = 0x01;
}
/*
* Function Name : magnet_off
* Input : NONE
* Output : Logic LOW at Pin H0
* Logic : PORTH is assigned to 0xFE which makes Pin H0 to have a Logic LOW
* Example call : magnet_off()
*
*/
void magnet_off()
{
PORTH = 0xFE;
}
//Servo related functions
/*
* Function Name : servo1_pin_config
* Input : NONE
* Output : Logic HIGH at Pin B5
* Logic : PORTB 5 is set as output pin .PORTB is assigned to 0x20 which makes Pin B5 to have a Logic HIGH
* Example call : servo1_pin_config
*
*/
void servo1_pin_config (void)
{
DDRB = DDRB | 0x20; //making PORTB 5 pin output
PORTB = PORTB | 0x20; //setting PORTB 5 pin to logic 1
}
/*
* Function Name : timer1_init
* Input : NONE
* Output : NONE
* Logic : TIMER1 initialization in 10 bit fast PWM mode,prescale:256, PWM 10bit fast, TOP=0x03FF, actual value: 52.25Hz
* Example call : timer1_init
*
*/
void timer1_init(void)
{
TCCR1B = 0x00; //stop
TCNT1H = 0xFC; //Counter high value to which OCR1xH value is to be compared with
TCNT1L = 0x01; //Counter low value to which OCR1xH value is to be compared with
OCR1AH = 0x03; //Output compare Register high value for servo 1
OCR1AL = 0xFF; //Output Compare Register low Value For servo 1
OCR1BH = 0x03; //Output compare Register high value for servo 2
OCR1BL = 0xFF; //Output Compare Register low Value For servo 2
OCR1CH = 0x03; //Output compare Register high value for servo 3
OCR1CL = 0xFF; //Output Compare Register low Value For servo 3
ICR1H = 0x03;
ICR1L = 0xFF;
TCCR1A = 0xAB; /*{COM1A1=1, COM1A0=0; COM1B1=1, COM1B0=0; COM1C1=1 COM1C0=0}
For Overriding normal port functionality to OCRnA outputs.
{WGM11=1, WGM10=1} Along With WGM12 in TCCR1B for Selecting FAST PWM Mode*/
TCCR1C = 0x00;
TCCR1B = 0x0C; //WGM12=1; CS12=1, CS11=0, CS10=0 (Prescaler=256)
}
/*
* Function Name : servo_1
* Input : NONE
* Output : NONE
* Logic : Setting the required Servo registers
* Example call : servo_1()
*
*/
void servo_1(unsigned char degrees)
{
float PositionPanServo = 0;
PositionPanServo = ((float)degrees / 1.86) + 35.0;
OCR1AH = 0x00;
OCR1AL = (unsigned char) PositionPanServo;
}
/*
* Function Name : servo_1_free
* Input : NONE
* Output : NONE
* Logic : makes servo 1 free rotating
* Example call : servo_1_free()
*
*/
void servo_1_free (void)
{
OCR1AH = 0x03;
OCR1AL = 0xFF; //Servo 1 off
}
// White line Sensor , Analog to digital converter functions
/*
* Function Name : adc_pin_config
* Input : None
* Output : None
* Logic : Configures pins of port F for ADC (as input)
* Example Call : adc_pin_config()
*
*/
void adc_pin_config (void)
{
DDRF = 0x00;
PORTF = 0x00;
}
/*
* Function Name : ADC_Conversion
* Input : ch - > channel
* Output : a - > Anallog value
* Logic : Function accepts the Channel Number and returns the corresponding Analog Value
* Example Call : 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; // Digital value of the analog input
}
/*
* Function Name : adc_init
* Input : None
* Output : None
* Logic : Functional resets/sets required ports/registers for ADC
* Example Call : adc_init()
*
*/
void adc_init()
{
ADCSRA = 0x00;
ADCSRB = 0x00; //MUX5 = 0
ADMUX = 0x20; //V ref=5V external --- ADLAR=1 --- MUX4:0 = 0000
ACSR = 0x80;
ADCSRA = 0x86; //ADEN=1 --- ADIE=1 --- ADPS2:0 = 1 1 0
}
//Buzzer related functions
/*
* Function Name : buzzer_pin_config
* Input : None
* Output : None
* Logic : Sets the pin j0 as output pin and initially it isn't supplied 5v
* Example Call : buzzer_pin_config()
*
*/
void buzzer_pin_config(void)
{
DDRJ = DDRJ | 0x01;
PORTJ = PORTJ & 0xFE;
}
/*
* Function Name : buzzer_on
* Input : None
* Output : None
* Logic : Supplies Logic High pin j0
* Example Call : buzzer_on()
*
*/
void buzzer_on(void)
{
PORTJ = 0x01;
}
/*
* Function Name : buzzer_off
* Input : None
* Output : None
* Logic : Sends Logic Low to pin j0
* Example Call : buzzer_off()
*
*/
void buzzer_off(void)
{ PORTJ = 0xFE;
}
/*
* Function Name : uart0_init
* Input : NONE
* Output : None
* Logic : Setting up UART for serial communication at baud rate 9600
* Example call : uart0_init()
*
*/
void uart0_init()
{
UCSR0B = 0x00; //disable while setting baud rate
UCSR0A = 0x00;
UCSR0C = 0x06;
UBRR0L = 0x5F; //9600BPS at 14745600Hz
UBRR0H = 0x00;
UCSR0B = 0x98;
//UCSR0C = 3<<1; //setting 8-bit character and 1 stop bit
//UCSR0B = RX | TX;
}
/*
* Function Name : ISR
* Input : NONE
* Output : None
* Logic : Handling all sending and receiving interrupts
* Example call : Called automatically
*
*/
ISR(USART0_RX_vect)
{
Data = UDR0;
}
/*
* Function Name : motor_pin_config
* Input : NONE
* Output : Register DDRA setting pins A0 to A3 as Output Port, Logic Low supplied to pins A0 to A3
* Logic : Masking of previous value of DDRA is done by bitwise 'or' operator with 0x0F. This sets only Pins A0 to A3 as output Pin
* Masking of previous value of PORTA is done by bitwise 'and' operator with 0xF0. Which sends logic LOW to pins A0 to A3
* Similarly DDRl and PORTL are assigned with 0x18 which sets pins L3 L4 as output pin and logic HIGH is supplied to them
* DDRE is and PORTE registers are assigned with 0xF0 which makes pins from A4 to A7 as output pins and Having Logic High
* Example call : motor_pin_config()
*
*/
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 Name : left_encoder_pin_config
* Input : None
* Output : None
* Logic : Function to configure INT4 (PORTE 4) pin as input for the left position encoder
* Example Call : left_encoder_pin_config()
*
*/
void left_encoder_pin_config (void)
{
DDRE = DDRE & 0xEF; //Set the direction of the PORTE 4 pin as input
PORTE = PORTE | 0x10; //Enable internal pull-up for PORTE 4 pin
}
/*
* Function Name : right_encoder_pin_config
* Input : None
* Output : None
* Logic : Function to configure INT5 (PORTE 5) pin as input for the right position encoder
* Example Call : right_encoder_pin_config()
*
*/
void right_encoder_pin_config (void)
{
DDRE = DDRE & 0xDF; //Set the direction of the PORTE 5 pin as input
PORTE = PORTE | 0x20; //Enable internal pull-up for PORTE 5 pin
}
/*
* Function Name : port_init
* Input : NONE
* Output : None
* Logic : A function to call all the pin configuration functions related to the ports
* Example call : port_init()
*
*/
void port_init()
{
motion_pin_config(); //robot motion pins config
left_encoder_pin_config(); //left encoder pin config
right_encoder_pin_config(); //right encoder pin config
servo1_pin_config();
magnet_pin_config();
}
/*
* Function Name : left_position_encoder_interrupt_init
* Input : None
* Output : None
* Logic : Function to enable Interrupt 4
* Example Call : left_position_encoder_interrupt_init()
*
*/
void left_position_encoder_interrupt_init (void)
{
cli(); //Clears the global interrupt
EICRB = EICRB | 0x02; // INT4 is set to trigger with falling edge
EIMSK = EIMSK | 0x10; // Enable Interrupt INT4 for left position encoder
sei(); // Enables the global interrupt
}
/*
* Function Name : right_position_encoder_interrupt_init
* Input : None
* Output : None
* Logic : Function to enable Interrupt 5
* Example Call : right_position_encoder_interrupt_init()
*
*/
void right_position_encoder_interrupt_init (void)
{
cli(); //Clears the global interrupt
EICRB = EICRB | 0x08; // INT5 is set to trigger with falling edge
EIMSK = EIMSK | 0x20; // Enable Interrupt INT5 for right position encoder
sei(); // Enables the global interrupt
}
/*
* Function Name : ISR
* Input : NONE
* Output : None
* Logic : ISR for right position encoder
* Example call : Called automatically
*
*/
ISR(INT5_vect)
{
ShaftCountRight++; //increment right shaft position count
}
/*
* Function Name : ISR
* Input : NONE
* Output : None
* Logic : ISR for left position encoder
* Example call : Called automatically
*
*/
ISR(INT4_vect)
{
ShaftCountLeft++; //increment left shaft position count
}
/*
* Function Name : motion_set
* Input : Direction - > Hexadecimal values on directions according to pins
* Output : PORTA = Direction in which the Motors have to move
* Logic : The Upper nibble is removed as it is not required from the Direction. The PORTA's original is assigned to variable PORTA_RESTORE,
* Lower nibble of the PORTA_RETORE is set to 0 and direction is added to the lower nibble. The current value of the variable PORTA_RESTORE
* is assigned to PORTA
* Example call : motion_set(0x0F)
*
*/
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
}
/*
* Function Name : forward
* Input : NONE
* Output : Call to function motion_set with Direction parameters ,call to function velocity with values of velocities of left and right motor
* Logic : A function call to motion_set(ox06) is made passing values of directions which makes the motors move in forward direction
* Example call : forward()
*
*/
void forward (void) //both wheels forward
{
motion_set(0x06);
}
/*
* Function Name : back
* Input : NONE
* Output : Call to function motion_set with Direction parameters ,call to function velocity with values of velocities of left and right motor
* Logic : A function call to motion_set(ox09) is made passing values of directions which makes the motors move in backward direction
* Example call : back()
*
*/
void back (void) //both wheels backward
{
motion_set(0x09);
}
/*
* Function Name : left
* Input : NONE
* Output : Call to function motion_set with Direction parameters, call to function velocity with values of velocities of left and right motor
* Logic : A function call to motion_set(0x05) is made passing values of directions, which makes the left motor to move backwards and right motor to move forward
* Example call : left()
*
*/
void left (void) //Left wheel backward, Right wheel forward
{
motion_set(0x05);
}
/*
* Function Name : right
* Input : NONE
* Output : Call to function motion_set with Direction parameters, call to function velocity with values of velocities of left and right motor
* Logic : A function call to motion_set(0x0A) is made passing values of directions, , which makes the left motor move upward and right motor in backwards direction
* Example call : right()
*
*/
void right (void) //Left wheel forward, Right wheel backward
{
motion_set(0x0A);
}
/*
* Function Name : soft_left
* Input : NONE
* Output : Call to function motion_set with Direction parameters, call to function velocity with values of velocities of left and right motor
* Logic : A function call to motion_set(0x04) is made passing values of directions, , which makes left wheel stationary, Right wheel forward
* Example call : soft_left()
*
*/
void soft_left (void)
{
motion_set(0x04);
}
/*
* Function Name : soft_left
* Input : NONE
* Output : Call to function motion_set with Direction parameters, call to function velocity with values of velocities of left and right motor
* Logic : A function call to motion_set(0x02) is made passing values of directions, , which makes left wheel forward, Right wheel is stationary
* Example call : soft_right()
*
*/
void soft_right (void)
{
motion_set(0x02);
}
/*
* Function Name : stop
* Input : NONE
* Output : Call to function motion_set with Direction parameters, call to function velocity with values of velocities of left and right motor
* Logic : A function call to motion_set(Direction) is made passing 0x00 to make the motors stop. 0x00 Makes all the output pins to get Logic LOW
* Example call : stop()
*
*/
void stop (void)
{
motion_set(0x00);
}
/*
* Function Name : angle_rotate
* Input : Degrees - > The degrees to move the bot to
* Output : None
* Logic : Function used for turning robot by specified degrees
* Example Call : angle_rotate(90)
*
*/
void angle_rotate(unsigned int Degrees)
{
float ReqdShaftCount = 0;
unsigned long int ReqdShaftCountInt = 0;
ReqdShaftCount = (float) Degrees/ 0.3721; // division by resolution to get shaft count
ReqdShaftCountInt = (unsigned int) ReqdShaftCount;
ShaftCountRight = 0;
ShaftCountLeft = 0;
while (1)
{
if((ShaftCountRight >= ReqdShaftCountInt) | (ShaftCountLeft >= ReqdShaftCountInt))
break;
}
stop(); //Stop robot
}
/*
*
* Function Name : timers_init
* Input : NONE
* Output : Timer 5 initialized in PWM mode for velocity control
* Logic : To program PWM 4 registers are needed to be initialized.
* TCCR5A - Timer counter control register A. Used to configure timer for PWM generation
* TCCR5B - Timer counter control register B. Used to control the timer.
* TCNT5 - 16 bit timer counter. Used to count up/down according to clock frequency
* OCR5N - 16 bit output compare register. Compares itself to TCNT5 and sets flags acoordingly.
* Example call : timers_init()
*
*/
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)
}
/*
* Function Name : velocity
* Input : unsigned char left_motor - > velocity of left motor; unsigned char right_motor - > velocity of right motor
* Output : Different values of voltage to the motors
* Logic : OCR5AL is a 16 bit output compare register. It compares itself from TCNT counter and sets flags when match occurs, indicating overflow.
* Example call : velocity
*
*/
void velocity (unsigned char right_motor, unsigned char left_motor)
{
OCR5AL = (unsigned char)right_motor;
OCR5BL = (unsigned char)left_motor;
}
/*
* Function Name : linear_distance_mm
* Input : DistanceInMM - > The distance to move the bot to
* Output : None
* Logic : Function used for moving robot in a direction by specified distance
* Example Call : linear_distance_mm(100)
*
*/
void linear_distance_mm(unsigned int DistanceInMM)
{
float ReqdShaftCount = 0;
unsigned long int ReqdShaftCountInt = 0;
ReqdShaftCount = DistanceInMM / 0.3721; // division by resolution to get shaft count
ReqdShaftCountInt = (unsigned long int) ReqdShaftCount;
ShaftCountRight = 0;
while(1)
{
if(ShaftCountRight > ReqdShaftCountInt)
{
break;
}
}
stop(); //Stop robot
}
/*
* Function Name : forward_mm
* Input : DistanceInMM - > The distance to move the bot to
* Output : None
* Logic : Function used for moving robot forward by specified distance
* Example Call : forward_mm(100)
*
*/
void forward_mm(unsigned int DistanceInMM)
{
forward();
linear_distance_mm(DistanceInMM);
}
/*
* Function Name : back_mm
* Input : DistanceInMM - > The distance to move the bot to
* Output : None
* Logic : Function used for moving robot Backward by specified distance
* Example Call : back_mm(100)
*
*/
void back_mm(unsigned int DistanceInMM)
{
back();
linear_distance_mm(DistanceInMM);
}
/*
* Function Name : left_degrees
* Input : Degrees - > The degrees to move the bot to
* Output : None
* Logic : Function used for moving robot by some degree from the left
* Example Call : left_degrees(90)
*
*/
void left_degrees(unsigned int Degrees)
{
// 88 pulses for 360 degrees rotation 4.090 degrees per count
left(); //Turn left
angle_rotate(Degrees);
}
/*
* Function Name : WhichRotation
* Input : Where - > data received through the uart
* Output : Bot movements according to the data received
* Logic : -
* Example call : WhichRotation('r')
*
*/
void WhichRotation(char Where)
{
//If the instruction is to move right
if (Where =='r')
{
// Velocity of the tires
velocity(150,150);
//Movement of the bot
while(1)
{
//Getting line sensor readings
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
//Setting motors to move as right
right();
//Making sure it moves and stops on the black line
//IF threshold is achieved at all the three sensors
if((Left_White_Line <= THRESHOLD) && (Center_White_Line >= THRESHOLD) && (Right_White_Line <= THRESHOLD))
{
//Put the velocities of motor as 0
velocity(0,0);
//Break Out of the loop as Movement is successful
break;
}
}
}
else if (Where =='b')
{
// Velocity of the tires
velocity(150,150);
//Movement of the bot
while(1)
{
//Getting line sensor readings
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
//Setting motors to move as backwards
back();
//Making sure it moves and stops on the black line
//IF threshold is achieved at all the three sensors
if((Left_White_Line <= THRESHOLD) && (Center_White_Line >= THRESHOLD) && (Right_White_Line <= THRESHOLD))
{
//Put the velocities of motor as 0
velocity(0,0);
//Break Out of the loop as Movement is successful
break;
}
}
}
else if (Where =='l')
{
//Setting the velocities
velocity(150,150);
//Movement of the bot
while(1)
{
//Getting line sensor readings
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
//Moving bot left
left();
//till back line is at center
if((Left_White_Line <= THRESHOLD) && (Center_White_Line >= THRESHOLD) && (Right_White_Line <= THRESHOLD))
{
velocity(0,0);
break;
}
}
}
}
/*
* Function Name : Bot_movement_common
* Input : NONE
* Output : None
* Logic : When call will made the bot move on the perfect black lines according to the threshold calculated
* Example call : Bot_movement_common()
*
*/
void Bot_movement_common(void)
{
//Setting velocities
velocity(176,180);
//Moving the bot
while(1)
{
// Getting Sensor readings
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
//Moving Forward
forward();
// IF reached on a node
if((Left_White_Line >= THRESHOLDNODE) && (Center_White_Line >= THRESHOLDNODE) && (Right_White_Line >= THRESHOLDNODE))
{
// Waiting to go a bit ahead of the node to take successful turns
//Stopping the bot and ending the moment
_delay_ms(60);
velocity(0,0);
break;
}
//If Black line shifts towards left
if((Left_White_Line<=THRESHOLD) && (Center_White_Line <= THRESHOLD )&& (Right_White_Line >= THRESHOLD))
{
velocity(180,180);
left();
}
//If Black line shifts a little towards left
if((Left_White_Line<=THRESHOLD) && (Center_White_Line >=THRESHOLD) && (Right_White_Line >= THRESHOLD))
{
velocity(180,180);
soft_left();
}
//If Black line is perfectly below the center sensor
if((Left_White_Line <= THRESHOLD) && (Center_White_Line >= THRESHOLD) && (Right_White_Line <= THRESHOLD))
{
velocity(150,150);
}
//If Black line shifts towards left
if((Left_White_Line>=THRESHOLD) && (Center_White_Line<=THRESHOLD) && (Right_White_Line<=THRESHOLD))
{
velocity(180,180);
right();
}
//If Black line shifts a little towards left
if(Left_White_Line>= THRESHOLD && Center_White_Line >= THRESHOLD && (Right_White_Line <= THRESHOLD))
{ velocity(180,180);
soft_right();
}
}
}
/*
* Function Name : Bot_movement_common2
* Input : NONE
* Output : None
* Logic : When call will made the bot move on the perfect black lines according to the threshold calculated (Difference is that is will stop the bot a little earlier when threshold is acheived on 3 sensors)
* Example call : Bot_movement_common2()
*
*/
void Bot_movement_common2(void)
{
//Setting velocities
velocity(95,108);
//Moving the bot
while(1)
{
// Getting Sensor readings
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
//Moving Forward
forward();
// IF reached on a node
if((Left_White_Line >= THRESHOLDNODE) && (Center_White_Line >= THRESHOLDNODE) && (Right_White_Line >= THRESHOLDNODE))
{
// Waiting to go a bit ahead of the node to take successful turns
//Stopping the bot and ending the moment
velocity(0,0);
stop();
break;
}
//If Black line shifts towards left
if((Left_White_Line<=THRESHOLD) && (Center_White_Line <= THRESHOLD )&& (Right_White_Line >= THRESHOLD))
{
velocity(180,180);
left();
}
//If Black line shifts a little towards left
if((Left_White_Line<=THRESHOLD) && (Center_White_Line >=THRESHOLD) && (Right_White_Line >= THRESHOLD))
{
velocity(180,180);
soft_left();
}
//If Black line is perfectly below the center sensor
if((Left_White_Line <= THRESHOLD) && (Center_White_Line >= THRESHOLD) && (Right_White_Line <= THRESHOLD))
{
velocity(150,150);
}