-
Notifications
You must be signed in to change notification settings - Fork 0
/
Line_Tracking.ino
828 lines (703 loc) · 28.8 KB
/
Line_Tracking.ino
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
#include <Servo.h>
#include <EEPROM.h>
#include <uSTimer2.h>
#include <CharliePlexM.h>
#include <Wire.h>
#include <I2CEncoder.h>
Servo servo_RightMotor;
Servo servo_LeftMotor;
Servo servo_ArmMotor;
Servo servo_GripMotor;
I2CEncoder encoder_RightMotor;
I2CEncoder encoder_LeftMotor;
// Uncomment keywords to enable debugging output
//#define DEBUG_MODE_DISPLAY
//#define DEBUG_MOTORS
//#define DEBUG_LINE_TRACKERS
//#define DEBUG_ENCODERS
//#define DEBUG_ULTRASONIC
//#define DEBUG_LINE_TRACKER_CALIBRATION
//#define DEBUG_MOTOR_CALIBRATION
boolean bt_Motors_Enabled = true;
//port pin constants+
const int ci_Ultrasonic_Ping = 2; //input plug
const int ci_Ultrasonic_Data = 3; //output plug
const int ci_Charlieplex_LED1 = 4;
const int ci_Charlieplex_LED2 = 5;
const int ci_Charlieplex_LED3 = 6;
const int ci_Charlieplex_LED4 = 7;
const int ci_Mode_Button = 7;
const int ci_Right_Motor = 9;
const int ci_Left_Motor = 8; //reversed motor pins on purpose
const int ci_Arm_Motor = 10;
const int ci_Grip_Motor = 11;
const int ci_Motor_Enable_Switch = 12;
const int ci_Right_Line_Tracker = A0;
const int ci_Middle_Line_Tracker = A1;
const int ci_Left_Line_Tracker = A2;
const int ci_Light_Sensor = A3;
const int ci_I2C_SDA = A4; // I2C data = white
const int ci_I2C_SCL = A5; // I2C clock = yellow
// Charlieplexing LED assignments
const int ci_Heartbeat_LED = 1;
const int ci_Indicator_LED = 4;
const int ci_Right_Line_Tracker_LED = 6;
const int ci_Middle_Line_Tracker_LED = 9;
const int ci_Left_Line_Tracker_LED = 12;
//constants
// EEPROM addresses
const int ci_Left_Line_Tracker_Dark_Address_L = 0;
const int ci_Left_Line_Tracker_Dark_Address_H = 1;
const int ci_Left_Line_Tracker_Light_Address_L = 2;
const int ci_Left_Line_Tracker_Light_Address_H = 3;
const int ci_Middle_Line_Tracker_Dark_Address_L = 4;
const int ci_Middle_Line_Tracker_Dark_Address_H = 5;
const int ci_Middle_Line_Tracker_Light_Address_L = 6;
const int ci_Middle_Line_Tracker_Light_Address_H = 7;
const int ci_Right_Line_Tracker_Dark_Address_L = 8;
const int ci_Right_Line_Tracker_Dark_Address_H = 9;
const int ci_Right_Line_Tracker_Light_Address_L = 10;
const int ci_Right_Line_Tracker_Light_Address_H = 11;
const int ci_Left_Motor_Offset_Address_L = 12;
const int ci_Left_Motor_Offset_Address_H = 13;
const int ci_Right_Motor_Offset_Address_L = 14;
const int ci_Right_Motor_Offset_Address_H = 15;
const int ci_Left_Motor_Stop = 1500; // 200 for brake mode; 1500 for stop
const int ci_Right_Motor_Stop = 1500;
const int ci_Grip_Motor_Open = 140; // Experiment to determine appropriate value
const int ci_Grip_Motor_Closed = 40;//old value they put ----- 90; // "
const int ci_Arm_Servo_Retracted = 55; //
const int ci_Arm_Servo_Extended = 120;//
const int ci_Display_Time = 500;
const int ci_Line_Tracker_Calibration_Interval = 100;
const int ci_Line_Tracker_Cal_Measures = 20;
const int ci_Line_Tracker_Tolerance = 50; // May need to adjust this
const int ci_Motor_Calibration_Cycles = 3;
const int ci_Motor_Calibration_Time = 5000;
//variables
byte b_LowByte;
byte b_HighByte;
unsigned long ul_Echo_Time;
unsigned int ui_Left_Line_Tracker_Data;
unsigned int ui_Middle_Line_Tracker_Data;
unsigned int ui_Right_Line_Tracker_Data;
unsigned int ui_Motors_Speed = 1700; // Default run speed////////////////////////////////////////////////////////////////////
unsigned int ui_Left_Motor_Speed;
unsigned int ui_Right_Motor_Speed;
long l_Left_Motor_Position;
long l_Right_Motor_Position;
unsigned long ul_3_Second_timer = 0;
unsigned long ul_Display_Time;
unsigned long ul_Calibration_Time;
unsigned long ui_Left_Motor_Offset;
unsigned long ui_Right_Motor_Offset;
unsigned int ui_Cal_Count;
unsigned int ui_Cal_Cycle;
unsigned int ui_Left_Line_Tracker_Dark;
unsigned int ui_Left_Line_Tracker_Light;
unsigned int ui_Middle_Line_Tracker_Dark;
unsigned int ui_Middle_Line_Tracker_Light;
unsigned int ui_Right_Line_Tracker_Dark;
unsigned int ui_Right_Line_Tracker_Light;
unsigned int ui_Line_Tracker_Tolerance;
unsigned int ui_Robot_State_Index = 0;
//0123456789ABCDEF
unsigned int ui_Mode_Indicator[6] = {
0x00, //B0000000000000000, //Stop
0x00FF, //B0000000011111111, //Run
0x0F0F, //B0000111100001111, //Calibrate line tracker light level
0x3333, //B0011001100110011, //Calibrate line tracker dark level
0xAAAA, //B1010101010101010, //Calibrate motors
0xFFFF //B1111111111111111 //Unused
};
unsigned int ui_Mode_Indicator_Index = 0;
//display Bits 0,1,2,3, 4, 5, 6, 7, 8, 9, 10, 11, 12, 13, 14, 15
int iArray[16] = {
1, 2, 4, 8, 16, 32, 64, 128, 256, 512, 1024, 2048, 4096, 8192, 16384, 65536
};
int iArrayIndex = 0;
boolean bt_Heartbeat = true;
boolean bt_3_S_Time_Up = false;
boolean bt_Do_Once = false;
boolean bt_Cal_Initialized = false;
////////////// created variables
boolean leftSenseOn = false;
boolean middleSenseOn = false;
boolean rightSenseOn = false;
char lastSoloLight = 's'; //s = straight, l = left, r = right
char operatingMode = 't'; //x = none, t = track line, l = turn left, r = turn right, s = scanning mode, f = finish mode, v = victory dance
boolean hasScanned = false;
////////////////////////////////////////////////////////
void setup() {
Wire.begin(); // Wire library required for I2CEncoder library
Serial.begin(9600);
CharliePlexM::setBtn(ci_Charlieplex_LED1, ci_Charlieplex_LED2,
ci_Charlieplex_LED3, ci_Charlieplex_LED4, ci_Mode_Button);
// set up ultrasonic
pinMode(ci_Ultrasonic_Ping, OUTPUT);
pinMode(ci_Ultrasonic_Data, INPUT);
// set up drive motors
pinMode(ci_Right_Motor, OUTPUT);
servo_RightMotor.attach(ci_Right_Motor);
pinMode(ci_Left_Motor, OUTPUT);
servo_LeftMotor.attach(ci_Left_Motor);
// set up arm motors
pinMode(ci_Arm_Motor, OUTPUT);
servo_ArmMotor.attach(ci_Arm_Motor);
pinMode(ci_Grip_Motor, OUTPUT);
servo_GripMotor.attach(ci_Grip_Motor);
// set up motor enable switch
pinMode(ci_Motor_Enable_Switch, INPUT);
// set up encoders. Must be initialized in order that they are chained together,
// starting with the encoder directly connected to the Arduino. See I2CEncoder docs
// for more information
encoder_LeftMotor.init(1.0 / 3.0 * MOTOR_393_SPEED_ROTATIONS, MOTOR_393_TIME_DELTA);
encoder_LeftMotor.setReversed(false); // adjust for positive count when moving forward
encoder_RightMotor.init(1.0 / 3.0 * MOTOR_393_SPEED_ROTATIONS, MOTOR_393_TIME_DELTA);
encoder_RightMotor.setReversed(true); // adjust for positive count when moving forward
// set up line tracking sensors
pinMode(ci_Right_Line_Tracker, INPUT);
pinMode(ci_Middle_Line_Tracker, INPUT);
pinMode(ci_Left_Line_Tracker, INPUT);
ui_Line_Tracker_Tolerance = ci_Line_Tracker_Tolerance;
// read saved values from EEPROM
b_LowByte = EEPROM.read(ci_Left_Line_Tracker_Dark_Address_L);
b_HighByte = EEPROM.read(ci_Left_Line_Tracker_Dark_Address_H);
ui_Left_Line_Tracker_Dark = word(b_HighByte, b_LowByte);
b_LowByte = EEPROM.read(ci_Left_Line_Tracker_Light_Address_L);
b_HighByte = EEPROM.read(ci_Left_Line_Tracker_Dark_Address_H);
ui_Left_Line_Tracker_Light = word(b_HighByte, b_LowByte);
b_LowByte = EEPROM.read(ci_Middle_Line_Tracker_Dark_Address_L);
b_HighByte = EEPROM.read(ci_Left_Line_Tracker_Dark_Address_H);
ui_Middle_Line_Tracker_Dark = word(b_HighByte, b_LowByte);
b_LowByte = EEPROM.read(ci_Middle_Line_Tracker_Light_Address_L);
b_HighByte = EEPROM.read(ci_Left_Line_Tracker_Dark_Address_H);
ui_Middle_Line_Tracker_Light = word(b_HighByte, b_LowByte);
b_LowByte = EEPROM.read(ci_Right_Line_Tracker_Dark_Address_L);
b_HighByte = EEPROM.read(ci_Left_Line_Tracker_Dark_Address_H);
ui_Right_Line_Tracker_Dark = word(b_HighByte, b_LowByte);
b_LowByte = EEPROM.read(ci_Right_Line_Tracker_Light_Address_L);
b_HighByte = EEPROM.read(ci_Left_Line_Tracker_Dark_Address_H);
ui_Right_Line_Tracker_Light = word(b_HighByte, b_LowByte);
b_LowByte = EEPROM.read(ci_Left_Motor_Offset_Address_L);
b_HighByte = EEPROM.read(ci_Left_Motor_Offset_Address_H);
ui_Left_Motor_Offset = word(b_HighByte, b_LowByte);
b_LowByte = EEPROM.read(ci_Right_Motor_Offset_Address_L);
b_HighByte = EEPROM.read(ci_Right_Motor_Offset_Address_H);
ui_Right_Motor_Offset = word(b_HighByte, b_LowByte);
}
void loop()
{
if ((millis() - ul_3_Second_timer) > 3000)
{
bt_3_S_Time_Up = true;
}
// button-based mode selection
if (CharliePlexM::ui_Btn)
{
if (bt_Do_Once == false)
{
bt_Do_Once = true;
ui_Robot_State_Index++;
ui_Robot_State_Index = ui_Robot_State_Index & 7;
ul_3_Second_timer = millis();
bt_3_S_Time_Up = false;
bt_Cal_Initialized = false;
ui_Cal_Cycle = 0;
}
}
else
{
bt_Do_Once = LOW;
}
// check if drive motors should be powered
bt_Motors_Enabled = digitalRead(ci_Motor_Enable_Switch);
// modes
// 0 = default after power up/reset
// 1 = Press mode button once to enter. Run robot.
// 2 = Press mode button twice to enter. Calibrate line tracker light level.
// 3 = Press mode button three times to enter. Calibrate line tracker dark level.
// 4 = Press mode button four times to enter. Calibrate motor speeds to drive straight.
switch (ui_Robot_State_Index)
{
case 0: //Robot stopped
{
readLineTrackers();
//Ping();
servo_LeftMotor.writeMicroseconds(ci_Left_Motor_Stop);
servo_RightMotor.writeMicroseconds(ci_Right_Motor_Stop);
servo_ArmMotor.write(ci_Arm_Servo_Retracted);
servo_GripMotor.write(ci_Grip_Motor_Closed);
encoder_LeftMotor.zero();
encoder_RightMotor.zero();
ui_Mode_Indicator_Index = 0;
disableArmMotors();
break;
}
case 1: //Robot Run after 3 seconds
{
if (bt_3_S_Time_Up)
{
readLineTrackers();
#ifdef DEBUG_ENCODERS
l_Left_Motor_Position = encoder_LeftMotor.getRawPosition();
l_Right_Motor_Position = encoder_RightMotor.getRawPosition();
Serial.print("Encoders L: ");
Serial.print(l_Left_Motor_Position);
Serial.print(", R: ");
Serial.println(l_Right_Motor_Position);
#endif
// constrain motor speeds
ui_Left_Motor_Speed = constrain(ui_Motors_Speed + ui_Left_Motor_Offset, 1600, 2100); //changed these
ui_Right_Motor_Speed = constrain(ui_Motors_Speed + ui_Right_Motor_Offset, 1600, 2100);
//**********************************************************************************************************************************************************************************************************************
//remember 1500 is 0 speed
disableArmMotors();
//Serial.println(operatingMode);
checkForOpMode();
//if (operatingMode != 'x'){operatingMode = 'v';}
if (operatingMode == 't'){lineTrack();}
else if (operatingMode == 'r'){rotateRight(ui_Right_Motor_Speed);} //numbers here are variable
else if (operatingMode == 'l'){rotateLeft(ui_Left_Motor_Speed);}
else if (operatingMode == 's'){scanForLight();hasScanned = true;}
else if (operatingMode == 'f'){finish();}
else if (operatingMode == 'x'){ui_Left_Motor_Speed = 1500;ui_Right_Motor_Speed = 1500;}
//setMaxSpeed(1600);
//***********************************************************************************************************************************************************************************************************************
if (bt_Motors_Enabled)
{
servo_LeftMotor.writeMicroseconds(ui_Left_Motor_Speed);
servo_RightMotor.writeMicroseconds(ui_Right_Motor_Speed);
}
else
{
servo_LeftMotor.writeMicroseconds(ci_Left_Motor_Stop);
servo_RightMotor.writeMicroseconds(ci_Right_Motor_Stop);
}
#ifdef DEBUG_MOTORS
Serial.print("Motors enabled: ");
Serial.print(bt_Motors_Enabled);
Serial.print(", Default: ");
Serial.print(ui_Motors_Speed);
Serial.print(", Left = ");
Serial.print(ui_Left_Motor_Speed);
Serial.print(", Right = ");
Serial.println(ui_Right_Motor_Speed);
#endif
ui_Mode_Indicator_Index = 1;
}
break;
}
case 2: //Calibrate line tracker light levels after 3 seconds
{
if (bt_3_S_Time_Up)
{
if (!bt_Cal_Initialized)
{
bt_Cal_Initialized = true;
ui_Left_Line_Tracker_Light = 0;
ui_Middle_Line_Tracker_Light = 0;
ui_Right_Line_Tracker_Light = 0;
ul_Calibration_Time = millis();
ui_Cal_Count = 0;
}
else if ((millis() - ul_Calibration_Time) > ci_Line_Tracker_Calibration_Interval)
{
ul_Calibration_Time = millis();
readLineTrackers();
ui_Left_Line_Tracker_Light += ui_Left_Line_Tracker_Data;
ui_Middle_Line_Tracker_Light += ui_Middle_Line_Tracker_Data;
ui_Right_Line_Tracker_Light += ui_Right_Line_Tracker_Data;
ui_Cal_Count++;
}
if (ui_Cal_Count == ci_Line_Tracker_Cal_Measures)
{
ui_Left_Line_Tracker_Light /= ci_Line_Tracker_Cal_Measures;
ui_Middle_Line_Tracker_Light /= ci_Line_Tracker_Cal_Measures;
ui_Right_Line_Tracker_Light /= ci_Line_Tracker_Cal_Measures;
#ifdef DEBUG_LINE_TRACKER_CALIBRATION
Serial.print("Light Levels: Left = ");
Serial.print(ui_Left_Line_Tracker_Light, DEC);
Serial.print(", Middle = ");
Serial.print(ui_Middle_Line_Tracker_Light, DEC);
Serial.print(", Right = ");
Serial.println(ui_Right_Line_Tracker_Light, DEC);
#endif
EEPROM.write(ci_Left_Line_Tracker_Light_Address_L, lowByte(ui_Left_Line_Tracker_Light));
EEPROM.write(ci_Left_Line_Tracker_Light_Address_H, highByte(ui_Left_Line_Tracker_Light));
EEPROM.write(ci_Middle_Line_Tracker_Light_Address_L, lowByte(ui_Middle_Line_Tracker_Light));
EEPROM.write(ci_Middle_Line_Tracker_Light_Address_H, highByte(ui_Middle_Line_Tracker_Light));
EEPROM.write(ci_Right_Line_Tracker_Light_Address_L, lowByte(ui_Right_Line_Tracker_Light));
EEPROM.write(ci_Right_Line_Tracker_Light_Address_H, highByte(ui_Right_Line_Tracker_Light));
ui_Robot_State_Index = 0; // go back to Mode 0
}
ui_Mode_Indicator_Index = 2;
}
break;
}
case 3: // Calibrate line tracker dark levels after 3 seconds
{
if (bt_3_S_Time_Up)
{
if (!bt_Cal_Initialized)
{
bt_Cal_Initialized = true;
ui_Left_Line_Tracker_Dark = 0;
ui_Middle_Line_Tracker_Dark = 0;
ui_Right_Line_Tracker_Dark = 0;
ul_Calibration_Time = millis();
ui_Cal_Count = 0;
}
else if ((millis() - ul_Calibration_Time) > ci_Line_Tracker_Calibration_Interval)
{
ul_Calibration_Time = millis();
readLineTrackers();
ui_Left_Line_Tracker_Dark += ui_Left_Line_Tracker_Data;
ui_Middle_Line_Tracker_Dark += ui_Middle_Line_Tracker_Data;
ui_Right_Line_Tracker_Dark += ui_Right_Line_Tracker_Data;
ui_Cal_Count++;
}
if (ui_Cal_Count == ci_Line_Tracker_Cal_Measures)
{
ui_Left_Line_Tracker_Dark /= ci_Line_Tracker_Cal_Measures;
ui_Middle_Line_Tracker_Dark /= ci_Line_Tracker_Cal_Measures;
ui_Right_Line_Tracker_Dark /= ci_Line_Tracker_Cal_Measures;
#ifdef DEBUG_LINE_TRACKER_CALIBRATION
Serial.print("Dark Levels: Left = ");
Serial.print(ui_Left_Line_Tracker_Dark, DEC);
Serial.print(", Middle = ");
Serial.print(ui_Middle_Line_Tracker_Dark, DEC);
Serial.print(", Right = ");
Serial.println(ui_Right_Line_Tracker_Dark, DEC);
#endif
EEPROM.write(ci_Left_Line_Tracker_Dark_Address_L, lowByte(ui_Left_Line_Tracker_Dark));
EEPROM.write(ci_Left_Line_Tracker_Dark_Address_H, highByte(ui_Left_Line_Tracker_Dark));
EEPROM.write(ci_Middle_Line_Tracker_Dark_Address_L, lowByte(ui_Middle_Line_Tracker_Dark));
EEPROM.write(ci_Middle_Line_Tracker_Dark_Address_H, highByte(ui_Middle_Line_Tracker_Dark));
EEPROM.write(ci_Right_Line_Tracker_Dark_Address_L, lowByte(ui_Right_Line_Tracker_Dark));
EEPROM.write(ci_Right_Line_Tracker_Dark_Address_H, highByte(ui_Right_Line_Tracker_Dark));
ui_Robot_State_Index = 0; // go back to Mode 0
}
ui_Mode_Indicator_Index = 3;
}
break;
}
case 4: //Calibrate motor straightness after 3 seconds.
{
if (bt_3_S_Time_Up)
{
if (!bt_Cal_Initialized)
{
bt_Cal_Initialized = true;
encoder_LeftMotor.zero();
encoder_RightMotor.zero();
ul_Calibration_Time = millis();
servo_LeftMotor.writeMicroseconds(ui_Motors_Speed);
servo_RightMotor.writeMicroseconds(ui_Motors_Speed);
}
else if ((millis() - ul_Calibration_Time) > ci_Motor_Calibration_Time)
{
servo_LeftMotor.writeMicroseconds(ci_Left_Motor_Stop);
servo_RightMotor.writeMicroseconds(ci_Right_Motor_Stop);
l_Left_Motor_Position = encoder_LeftMotor.getRawPosition();
l_Right_Motor_Position = encoder_RightMotor.getRawPosition();
if (l_Left_Motor_Position > l_Right_Motor_Position)
{
// May have to update this if different calibration time is used
ui_Right_Motor_Offset = 0;
ui_Left_Motor_Offset = (l_Left_Motor_Position - l_Right_Motor_Position) / 4;
}
else
{
// May have to update this if different calibration time is used
ui_Right_Motor_Offset = (l_Right_Motor_Position - l_Left_Motor_Position) / 4;
ui_Left_Motor_Offset = 0;
}
#ifdef DEBUG_MOTOR_CALIBRATION
Serial.print("Motor Offsets: Left = ");
Serial.print(ui_Left_Motor_Offset);
Serial.print(", Right = ");
Serial.println(ui_Right_Motor_Offset);
#endif
EEPROM.write(ci_Right_Motor_Offset_Address_L, lowByte(ui_Right_Motor_Offset));
EEPROM.write(ci_Right_Motor_Offset_Address_H, highByte(ui_Right_Motor_Offset));
EEPROM.write(ci_Left_Motor_Offset_Address_L, lowByte(ui_Left_Motor_Offset));
EEPROM.write(ci_Left_Motor_Offset_Address_H, highByte(ui_Left_Motor_Offset));
ui_Robot_State_Index = 0; // go back to Mode 0
}
#ifdef DEBUG_MOTOR_CALIBRATION
Serial.print("Encoders L: ");
Serial.print(encoder_LeftMotor.getRawPosition());
Serial.print(", R: ");
Serial.println(encoder_RightMotor.getRawPosition());
#endif
ui_Mode_Indicator_Index = 4;
}
break;
}
}
if ((millis() - ul_Display_Time) > ci_Display_Time)
{
ul_Display_Time = millis();
#ifdef DEBUG_MODE_DISPLAY
Serial.print("Mode: ");
Serial.println(ui_Mode_Indicator[ui_Mode_Indicator_Index], DEC);
#endif
bt_Heartbeat = !bt_Heartbeat;
CharliePlexM::Write(ci_Heartbeat_LED, bt_Heartbeat);
digitalWrite(13, bt_Heartbeat);
Indicator();
}
}
// set mode indicator LED state
void Indicator()
{
//display routine, if true turn on led
CharliePlexM::Write(ci_Indicator_LED, !(ui_Mode_Indicator[ui_Mode_Indicator_Index] &
(iArray[iArrayIndex])));
iArrayIndex++;
iArrayIndex = iArrayIndex & 15;
}
// read values from line trackers and update status of line tracker LEDs =>> also set bool variables to help
void readLineTrackers()
{
ui_Left_Line_Tracker_Data = analogRead(ci_Left_Line_Tracker);
ui_Middle_Line_Tracker_Data = analogRead(ci_Middle_Line_Tracker);
ui_Right_Line_Tracker_Data = analogRead(ci_Right_Line_Tracker);
//left light sensor over line
if (ui_Left_Line_Tracker_Data < (ui_Left_Line_Tracker_Dark - ui_Line_Tracker_Tolerance))
{
CharliePlexM::Write(ci_Left_Line_Tracker_LED, HIGH);
leftSenseOn = true;
lastSoloLight = 'l';
}
else
{
CharliePlexM::Write(ci_Left_Line_Tracker_LED, LOW);
leftSenseOn = false;
}
//middle light sensor over line
if (ui_Middle_Line_Tracker_Data < (ui_Middle_Line_Tracker_Dark - ui_Line_Tracker_Tolerance))
{
CharliePlexM::Write(ci_Middle_Line_Tracker_LED, HIGH);
middleSenseOn = true;
}
else
{
CharliePlexM::Write(ci_Middle_Line_Tracker_LED, LOW);
middleSenseOn = false;
}
//right light sesnor over
if (ui_Right_Line_Tracker_Data < (ui_Right_Line_Tracker_Dark - ui_Line_Tracker_Tolerance))
{
CharliePlexM::Write(ci_Right_Line_Tracker_LED, HIGH);
rightSenseOn = true;
lastSoloLight = 'r';
}
else
{
CharliePlexM::Write(ci_Right_Line_Tracker_LED, LOW);
rightSenseOn = false;
}
#ifdef DEBUG_LINE_TRACKERS
Serial.print("Trackers: Left = ");
Serial.print(ui_Left_Line_Tracker_Data, DEC);
Serial.print(", Middle = ");
Serial.print(ui_Middle_Line_Tracker_Data, DEC);
Serial.print(", Right = ");
Serial.println(ui_Right_Line_Tracker_Data, DEC);
#endif
}
// measure distance to target using ultrasonic sensor
void Ping()
{
//Ping Ultrasonic
//Send the Ultrasonic Range Finder a 10 microsecond pulse per tech spec
digitalWrite(ci_Ultrasonic_Ping, HIGH);
delayMicroseconds(10); //The 10 microsecond pause where the pulse in "high"
digitalWrite(ci_Ultrasonic_Ping, LOW);
//use command pulseIn to listen to Ultrasonic_Data pin to record the
//time that it takes from when the Pin goes HIGH until it goes LOW
ul_Echo_Time = pulseIn(ci_Ultrasonic_Data, HIGH, 10000);
// Print Sensor Readings
#ifdef DEBUG_ULTRASONIC
Serial.print("Time (microseconds): ");
Serial.print(ul_Echo_Time, DEC);
Serial.print(", Inches: ");
Serial.print(ul_Echo_Time / 148); //divide time by 148 to get distance in inches
Serial.print(", cm: ");
Serial.println(ul_Echo_Time / 58); //divide time by 58 to get distance in cm
#endif
}
//ADDED FUNCTIONS//
void lineTrack()
{
if (rightSenseOn) //only right sensor on
{
ui_Right_Motor_Speed = 1625;
ui_Left_Motor_Speed = 1700;
}
else if (leftSenseOn) //only left sensor on
{
ui_Left_Motor_Speed = 1550;
ui_Right_Motor_Speed = 1700;
}
else if (!rightSenseOn && !middleSenseOn && !leftSenseOn) //no sensors are on (failsafe)
{
switch (lastSoloLight)
{
case 'l':
ui_Left_Motor_Speed = 1700; //change to fix maybe
ui_Right_Motor_Speed = 1500;
case 'r':
ui_Right_Motor_Speed = 1500;
ui_Left_Motor_Speed = 1700;
}
}
else if (rightSenseOn && middleSenseOn && leftSenseOn) //all sensors on (end of track)
{
ui_Left_Motor_Speed = 1500;
ui_Right_Motor_Speed = 1500;
}
}
void setMaxSpeed(int maxSpeed) //this function just prevents the robot from exceding a specified speed from 1500 -> (assuming that is 0)
{
ui_Right_Motor_Speed = constrain(ui_Right_Motor_Speed,1500 - ui_Left_Motor_Offset - (maxSpeed - 1500),maxSpeed);
ui_Left_Motor_Speed = constrain(ui_Left_Motor_Speed,1500 - ui_Left_Motor_Offset - (maxSpeed - 1500),maxSpeed);
}
//ALSO NOTE "SPEED" IS NOT REALLY SPEED. IT IS THE POWER AND VARIES BY THE INPUT VOLTAGE
void rotateRight(int turningSpeed) //remember that 1500 is 0 //also note full wheel turn is 614 on the encoder
{
ui_Right_Motor_Speed = 1500 - ui_Right_Motor_Offset - (turningSpeed - 1500); //subtract the speed from offset and "0 speed"
ui_Left_Motor_Speed = turningSpeed;
}
void rotateLeft(int turningSpeed) //remember that 1500 is 0
{
ui_Right_Motor_Speed = turningSpeed;
ui_Left_Motor_Speed = 1500 - ui_Left_Motor_Offset - (turningSpeed - 1500); //subtract the speed from offset and "0 speed"
}
void checkForOpMode() //maybe add a parameter to indicate which way it is turning first, left or right
{
if (leftSenseOn && middleSenseOn && rightSenseOn && operatingMode == 't') //if end of track is reached ==> turn to turning mode
{
operatingMode = 'l'; //////////////////////////////////////This value changes whether you turn left first or right first
encoder_RightMotor.zero();
encoder_LeftMotor.zero();
}
else if ((leftSenseOn || middleSenseOn || rightSenseOn) && encoder_LeftMotor.getRawPosition() > 310 && operatingMode == 'r') //check left encoder for right turn; right encoder for left turn //ps the encoder pos is pretty arbitrary
{
if (!hasScanned){operatingMode = 's';}
else {operatingMode = 'f';}
}
else if ((leftSenseOn || middleSenseOn || rightSenseOn) && encoder_RightMotor.getRawPosition() > 310 && operatingMode == 'l')
{
if (!hasScanned){operatingMode = 's';}
else {operatingMode = 'f';}
}
}
void writeToMotors()
{
servo_LeftMotor.writeMicroseconds(ui_Left_Motor_Speed);
servo_RightMotor.writeMicroseconds(ui_Right_Motor_Speed);
}
void scanForLight()////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////////scanning
{
if (!(leftSenseOn && middleSenseOn && rightSenseOn)){lineTrack();}
else if (leftSenseOn && middleSenseOn && rightSenseOn)
{
//insert all the code for the scanning
//operatingMode = 'x'; //used to stop
//stop motors and reset encoders
ui_Right_Motor_Speed = 200;
ui_Left_Motor_Speed = 200;
writeToMotors();
encoder_RightMotor.zero();
encoder_LeftMotor.zero();
servo_ArmMotor.attach(ci_Arm_Motor);
servo_ArmMotor.write(100);
while (encoder_RightMotor.getRawPosition() > -100) //rotate right until it reaches a certain point
{
rotateRight(1600);
writeToMotors();
}
for (int i = 0; analogRead(ci_Light_Sensor) > 105; i++)
{
if (i % 2 == 0){rotateLeft(1600);}
else {ui_Right_Motor_Speed = 1500; ui_Left_Motor_Speed = 1500;}
writeToMotors();
}
ui_Right_Motor_Speed = 1500;
ui_Left_Motor_Speed = 1500;
writeToMotors();
servo_GripMotor.attach(ci_Grip_Motor);
servo_GripMotor.write(ci_Grip_Motor_Open);
delay(1000);
encoder_RightMotor.zero();
encoder_LeftMotor.zero();
while ((encoder_RightMotor.getRawPosition() + encoder_LeftMotor.getRawPosition())/2 < 12)
{ui_Right_Motor_Speed = 1620;ui_Left_Motor_Speed = 1600;writeToMotors();}
delay(1000);
servo_GripMotor.write(ci_Grip_Motor_Closed);
delay(1000);
delay(1000);
servo_ArmMotor.write(80);
encoder_RightMotor.zero();
encoder_LeftMotor.zero();
while (encoder_RightMotor.getRawPosition() > -100) //rotate right until it reaches a certain point
{
rotateRight(1600);
writeToMotors();
}
delay(1000);
//detect next line for finish mode
while (!leftSenseOn || !middleSenseOn || !rightSenseOn)
{ui_Right_Motor_Speed = 1600;ui_Left_Motor_Speed = 1600;
writeToMotors();}
//switch to finish mode
operatingMode = 'f';
}
}
void disableArmMotors()//to distibute power efficently when arm is not needed
{
servo_GripMotor.detach();
servo_ArmMotor.detach();
}
void finish()
{
if (!(leftSenseOn && middleSenseOn && rightSenseOn)){lineTrack();}//initate lineTracking after scanning mode
else if (leftSenseOn && middleSenseOn && rightSenseOn)//reached end of track
{
servo_GripMotor.attach(ci_Grip_Motor);//re attach arm and grip
servo_ArmMotor.attach(ci_Arm_Motor);
encoder_RightMotor.zero();
encoder_LeftMotor.zero();
while (encoder_LeftMotor.getRawPosition() > -100) //rotate left until it reaches a certain point
{
rotateLeft(1600);
writeToMotors();
}
delay(1000);
encoder_RightMotor.zero();
encoder_LeftMotor.zero();
while ("poop"){
ui_Right_Motor_Speed = 1617;ui_Left_Motor_Speed = 1600;
servo_LeftMotor.writeMicroseconds(ui_Left_Motor_Speed);//write to motors
servo_RightMotor.writeMicroseconds(ui_Right_Motor_Speed);
Serial.println(encoder_LeftMotor.getRawPosition());
if (encoder_LeftMotor.getRawPosition() >1550)//go forward 1550 encoder positions
{ui_Right_Motor_Speed = 1500;ui_Left_Motor_Speed = 1500;
servo_LeftMotor.writeMicroseconds(ui_Left_Motor_Speed);
servo_RightMotor.writeMicroseconds(ui_Right_Motor_Speed);
break;}
}
servo_ArmMotor.write(120);//extend arm
delay(1000);
servo_GripMotor.write(140);
servo_GripMotor.write(ci_Grip_Motor_Open);
servo_GripMotor.write(ci_Grip_Motor_Open);
servo_GripMotor.write(ci_Grip_Motor_Open);
servo_GripMotor.write(ci_Grip_Motor_Open);
delay(1000);
operatingMode = 'x';
}
}