-
Notifications
You must be signed in to change notification settings - Fork 0
/
car.cpp
2131 lines (2001 loc) · 69 KB
/
car.cpp
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
/*
* @Author: ELEGOO
* @Date: 2019-10-22 11:59:09
* @LastEditTime: 2021-01-05 09:30:14
* @LastEditors: Changhua
* @Description: Smart Robot Car V4.0
* @FilePath:
*/
#include <avr/wdt.h>
//#include <hardwareSerial.h>
#include <stdio.h>
#include <string.h>
#include <limits.h>
#include "car.h"
#include "DeviceDriverSet_xxx0.h"
#include "ArduinoJson-v6.11.1.h" //ArduinoJson
#include "MPU6050_getdata.h"
#define US_ROTATION_INITIAL 90
#define US_ROTATION_STEP 30
#define US_COLLISION_DISTANCE 20
#define CAR_CRUISE_SPEED 100
#define CAR_TURN_SPEED 50
#define CAR_TURN_INTERVAL_MS 100
#define CAR_TURN_TOLERANCE_DEG 10
#define SEMAPHORE_GREEN 0xF00DCAFE
#define SEMAPHORE_RED 0xDEADC0DE
#define _is_print 1
#define _Test_print 0
Car Application_FunctionSet;
IRrecv IRReceiver(9);
/*Hardware device object list*/
MPU6050_getdata AppMPU6050getdata;
DeviceDriverSet_RBGLED AppRBG_LED;
DeviceDriverSet_Key AppKey;
DeviceDriverSet_ITR20001 AppITR20001;
DeviceDriverSet_Voltage AppVoltage;
DeviceDriverSet_Motor AppMotor;
DeviceDriverSet_ULTRASONIC AppULTRASONIC;
DeviceDriverSet_Servo AppServo;
DeviceDriverSet_IRrecv AppIRrecv;
int contatore = 0;
/*f(x) int */
static boolean
valueWithin(long x, long s, long e) //f(x)
{
if (s <= x && x <= e)
return true;
else
return false;
}
static void
delayMS(uint16_t _ms)
{
wdt_reset();
for (unsigned long i = 0; i < _ms; i++)
{
delay(1);
}
}
/*Movement Direction Control List*/
enum SmartRobotCarMotionControl
{
Forward, //(1)
Backward, //(2)
Left, //(3)
Right, //(4)
LeftForward, //(5)
LeftBackward, //(6)
RightForward, //(7)
RightBackward, //(8)
stop_it //(9)
}; //direction方向:(1)、(2)、 (3)、(4)、(5)、(6)
/*Mode Control List*/
enum SmartRobotCarFunctionalModel
{
Standby_mode, /*Standby Mode*/
TraceBased_mode, /*Line Tracking Mode*/
ObstacleAvoidance_mode, /*Obstacle Avoidance Mode*/
Follow_mode, /*Following Mode*/
Rocker_mode, /*Rocker Control Mode*/
CMD_inspect,
CMD_Programming_mode, /*Programming Mode*/
CMD_ClearAllFunctions_Standby_mode, /*Clear All Functions And Enter Standby Mode*/
CMD_ClearAllFunctions_Programming_mode, /*Clear All Functions And Enter Programming Mode*/
CMD_MotorControl, /*Motor Control Mode*/
CMD_CarControl_TimeLimit, /*Car Movement Direction Control With Time Limit*/
CMD_CarControl_NoTimeLimit, /*Car Movement Direction Control Without Time Limit*/
CMD_MotorControl_Speed, /*Motor Speed Control*/
CMD_ServoControl, /*Servo Motor Control*/
CMD_LightingControl_TimeLimit, /*RGB Lighting Control With Time Limit*/
CMD_LightingControl_NoTimeLimit, /*RGB Lighting Control Without Time Limit*/
};
/*Application Management list*/
struct Application_xxx
{
SmartRobotCarMotionControl Motion_Control;
SmartRobotCarFunctionalModel Functional_Mode;
unsigned long CMD_CarControl_Millis;
unsigned long CMD_LightingControl_Millis;
};
Application_xxx Application_SmartRobotCarxxx0;
bool ApplicationFunctionSet_SmartRobotCarLeaveTheGround(void);
void ApplicationFunctionSet_SmartRobotCarLinearMotionControl(SmartRobotCarMotionControl direction, uint8_t directionRecord, uint8_t speed, uint8_t Kp, uint8_t UpperLimit);
void ApplicationFunctionSet_SmartRobotCarMotionControl(SmartRobotCarMotionControl direction, uint8_t is_speed);
void Car::ApplicationFunctionSet_Init(void)
{
bool res_error = true;
Serial.begin(9600);
AppVoltage.DeviceDriverSet_Voltage_Init();
AppMotor.DeviceDriverSet_Motor_Init();
AppServo.DeviceDriverSet_Servo_Init(90);
AppKey.DeviceDriverSet_Key_Init();
AppRBG_LED.DeviceDriverSet_RBGLED_Init(20);
AppIRrecv.DeviceDriverSet_IRrecv_Init();
Serial.println("Initialized IR Receiver");
AppULTRASONIC.DeviceDriverSet_ULTRASONIC_Init();
AppITR20001.DeviceDriverSet_ITR20001_Init();
res_error = AppMPU6050getdata.MPU6050_dveInit();
AppMPU6050getdata.MPU6050_calibration();
// Initialize IR Receiver
IRReceiver.enableIRIn();
Serial.println("Enabled IR Receiver");
Application_SmartRobotCarxxx0.Functional_Mode = ObstacleAvoidance_mode;
}
/*ITR20001 Check if the car leaves the ground*/
static bool ApplicationFunctionSet_SmartRobotCarLeaveTheGround(void)
{
if (AppITR20001.DeviceDriverSet_ITR20001_getAnaloguexxx_R() > Application_FunctionSet.TrackingDetection_V &&
AppITR20001.DeviceDriverSet_ITR20001_getAnaloguexxx_M() > Application_FunctionSet.TrackingDetection_V &&
AppITR20001.DeviceDriverSet_ITR20001_getAnaloguexxx_L() > Application_FunctionSet.TrackingDetection_V)
{
Application_FunctionSet.Car_LeaveTheGround = false;
return false;
}
else
{
Application_FunctionSet.Car_LeaveTheGround = true;
return true;
}
}
/*
Straight line movement control:For dual-drive motors, due to frequent motor coefficient deviations and many external interference factors,
it is difficult for the car to achieve relative Straight line movement. For this reason, the feedback of the yaw control loop is added.
direction:only forward/backward
directionRecord:Used to update the direction and position data (Yaw value) when entering the function for the first time.
speed:the speed range is 0~255
Kp:Position error proportional constant(The feedback of improving location resuming status,will be modified according to different mode),improve damping control.
UpperLimit:Maximum output upper limit control
*/
static void ApplicationFunctionSet_SmartRobotCarLinearMotionControl(SmartRobotCarMotionControl direction, uint8_t directionRecord, uint8_t speed, uint8_t Kp, uint8_t UpperLimit)
{
static float Yaw; //Yaw
static float yaw_So = 0;
static uint8_t en = 110;
static unsigned long is_time;
if (en != directionRecord || millis() - is_time > 10)
{
AppMotor.DeviceDriverSet_Motor_control(/*direction_A*/ direction_void, /*speed_A*/ 0,
/*direction_B*/ direction_void, /*speed_B*/ 0, /*controlED*/ control_enable); //Motor control
AppMPU6050getdata.MPU6050_dveGetEulerAngles(&Yaw);
is_time = millis();
}
//if (en != directionRecord)
if (en != directionRecord || Application_FunctionSet.Car_LeaveTheGround == false)
{
en = directionRecord;
yaw_So = Yaw;
}
//Add proportional constant Kp to increase rebound effect
int R = (Yaw - yaw_So) * Kp + speed;
if (R > UpperLimit)
{
R = UpperLimit;
}
else if (R < 10)
{
R = 10;
}
int L = (yaw_So - Yaw) * Kp + speed;
if (L > UpperLimit)
{
L = UpperLimit;
}
else if (L < 10)
{
L = 10;
}
if (direction == Forward) //Forward
{
AppMotor.DeviceDriverSet_Motor_control(/*direction_A*/ direction_just, /*speed_A*/ R,
/*direction_B*/ direction_just, /*speed_B*/ L, /*controlED*/ control_enable);
}
else if (direction == Backward) //Backward
{
AppMotor.DeviceDriverSet_Motor_control(/*direction_A*/ direction_back, /*speed_A*/ L,
/*direction_B*/ direction_back, /*speed_B*/ R, /*controlED*/ control_enable);
}
}
/*
Movement Direction Control:
Input parameters: 1# direction:Forward(1)、Backward(2)、 Left(3)、Right(4)、LeftForward(5)、LeftBackward(6)、RightForward(7)RightBackward(8)
2# speed(0--255)
*/
static void ApplicationFunctionSet_SmartRobotCarMotionControl(SmartRobotCarMotionControl direction, uint8_t is_speed)
{
Car Application_FunctionSet;
static uint8_t directionRecord = 0;
uint8_t Kp, UpperLimit;
uint8_t speed = is_speed;
//Control mode that requires straight line movement adjustment(Car will has movement offset easily in the below mode,the movement cannot achieve the effect of a relatively straight direction
//so it needs to add control adjustment)
switch (Application_SmartRobotCarxxx0.Functional_Mode)
{
case Rocker_mode:
Kp = 10;
UpperLimit = 255;
break;
case ObstacleAvoidance_mode:
Kp = 2;
UpperLimit = 180;
break;
case Follow_mode:
Kp = 2;
UpperLimit = 180;
break;
case CMD_CarControl_TimeLimit:
Kp = 2;
UpperLimit = 180;
break;
case CMD_CarControl_NoTimeLimit:
Kp = 2;
UpperLimit = 180;
break;
default:
Kp = 10;
UpperLimit = 255;
break;
}
switch (direction)
{
case /* constant-expression */
Forward:
/* code */
if (Application_SmartRobotCarxxx0.Functional_Mode == TraceBased_mode)
{
AppMotor.DeviceDriverSet_Motor_control(/*direction_A*/ direction_just, /*speed_A*/ speed,
/*direction_B*/ direction_just, /*speed_B*/ speed, /*controlED*/ control_enable); //Motor control
}
else
{ //When moving forward, enter the direction and position approach control loop processing
ApplicationFunctionSet_SmartRobotCarLinearMotionControl(Forward, directionRecord, speed, Kp, UpperLimit);
directionRecord = 1;
}
break;
case /* constant-expression */ Backward:
/* code */
if (Application_SmartRobotCarxxx0.Functional_Mode == TraceBased_mode)
{
AppMotor.DeviceDriverSet_Motor_control(/*direction_A*/ direction_back, /*speed_A*/ speed,
/*direction_B*/ direction_back, /*speed_B*/ speed, /*controlED*/ control_enable); //Motor control
}
else
{ //When moving backward, enter the direction and position approach control loop processing
ApplicationFunctionSet_SmartRobotCarLinearMotionControl(Backward, directionRecord, speed, Kp, UpperLimit);
directionRecord = 2;
}
break;
case /* constant-expression */ Left:
/* code */
directionRecord = 3;
AppMotor.DeviceDriverSet_Motor_control(/*direction_A*/ direction_just, /*speed_A*/ speed,
/*direction_B*/ direction_back, /*speed_B*/ speed, /*controlED*/ control_enable); //Motor control
break;
case /* constant-expression */ Right:
/* code */
directionRecord = 4;
AppMotor.DeviceDriverSet_Motor_control(/*direction_A*/ direction_back, /*speed_A*/ speed,
/*direction_B*/ direction_just, /*speed_B*/ speed, /*controlED*/ control_enable); //Motor control
break;
case /* constant-expression */ LeftForward:
/* code */
directionRecord = 5;
AppMotor.DeviceDriverSet_Motor_control(/*direction_A*/ direction_just, /*speed_A*/ speed,
/*direction_B*/ direction_just, /*speed_B*/ speed / 2, /*controlED*/ control_enable); //Motor control
break;
case /* constant-expression */ LeftBackward:
/* code */
directionRecord = 6;
AppMotor.DeviceDriverSet_Motor_control(/*direction_A*/ direction_back, /*speed_A*/ speed,
/*direction_B*/ direction_back, /*speed_B*/ speed / 2, /*controlED*/ control_enable); //Motor control
break;
case /* constant-expression */ RightForward:
/* code */
directionRecord = 7;
AppMotor.DeviceDriverSet_Motor_control(/*direction_A*/ direction_just, /*speed_A*/ speed / 2,
/*direction_B*/ direction_just, /*speed_B*/ speed, /*controlED*/ control_enable); //Motor control
break;
case /* constant-expression */ RightBackward:
/* code */
directionRecord = 8;
AppMotor.DeviceDriverSet_Motor_control(/*direction_A*/ direction_back, /*speed_A*/ speed / 2,
/*direction_B*/ direction_back, /*speed_B*/ speed, /*controlED*/ control_enable); //Motor control
break;
case /* constant-expression */ stop_it:
/* code */
directionRecord = 9;
AppMotor.DeviceDriverSet_Motor_control(/*direction_A*/ direction_void, /*speed_A*/ 0,
/*direction_B*/ direction_void, /*speed_B*/ 0, /*controlED*/ control_enable); //Motor control
break;
default:
directionRecord = 10;
break;
}
}
/*
Robot car update sensors' data:Partial update (selective update)
*/
void Car::ApplicationFunctionSet_SensorDataUpdate(void)
{
// AppMotor.DeviceDriverSet_Motor_Test();
{ /*Battery voltage status update*/
static unsigned long VoltageData_time = 0;
static int VoltageData_number = 1;
if (millis() - VoltageData_time > 10) //read and update the data per 10ms
{
VoltageData_time = millis();
VoltageData_V = AppVoltage.DeviceDriverSet_Voltage_getAnalogue();
if (VoltageData_V < VoltageDetection)
{
VoltageData_number++;
if (VoltageData_number == 500) //Continuity to judge the latest voltage value multiple
{
VoltageDetectionStatus = true;
VoltageData_number = 0;
}
}
else
{
VoltageDetectionStatus = false;
}
}
}
// { /*value updation for the ultrasonic sensor:for the Obstacle Avoidance mode*/
// AppULTRASONIC.DeviceDriverSet_ULTRASONIC_Get(&UltrasoundData_cm /*out*/);
// UltrasoundDetectionStatus = function_xxx(UltrasoundData_cm, 0, ObstacleDetection);
// }
{ /*value updation for the IR sensors on the line tracking module:for the line tracking mode*/
TrackingData_R = AppITR20001.DeviceDriverSet_ITR20001_getAnaloguexxx_R();
TrackingDetectionStatus_R = valueWithin(TrackingData_R, TrackingDetection_S, TrackingDetection_E);
TrackingData_M = AppITR20001.DeviceDriverSet_ITR20001_getAnaloguexxx_M();
TrackingDetectionStatus_M = valueWithin(TrackingData_M, TrackingDetection_S, TrackingDetection_E);
TrackingData_L = AppITR20001.DeviceDriverSet_ITR20001_getAnaloguexxx_L();
TrackingDetectionStatus_L = valueWithin(TrackingData_L, TrackingDetection_S, TrackingDetection_E);
//ITR20001 Check if the car leaves the ground
ApplicationFunctionSet_SmartRobotCarLeaveTheGround();
}
// acquire timestamp
// static unsigned long Test_time;
// if (millis() - Test_time > 200)
// {
// Test_time = millis();
// //AppITR20001.DeviceDriverSet_ITR20001_Test();
// }
}
/*
Startup operation requirement:
*/
void Car::ApplicationFunctionSet_Bootup(void)
{
Application_SmartRobotCarxxx0.Functional_Mode = Standby_mode;
}
static void CMD_Lighting(uint8_t is_LightingSequence, int8_t is_LightingColorValue_R, uint8_t is_LightingColorValue_G, uint8_t is_LightingColorValue_B)
{
switch (is_LightingSequence)
{
case 0:
AppRBG_LED.DeviceDriverSet_RBGLED_Color(NUM_LEDS, is_LightingColorValue_R, is_LightingColorValue_G, is_LightingColorValue_B);
break;
case 1: /*Left*/
AppRBG_LED.DeviceDriverSet_RBGLED_Color(3, is_LightingColorValue_R, is_LightingColorValue_G, is_LightingColorValue_B);
break;
case 2: /*Forward*/
AppRBG_LED.DeviceDriverSet_RBGLED_Color(2, is_LightingColorValue_R, is_LightingColorValue_G, is_LightingColorValue_B);
break;
case 3: /*Right*/
AppRBG_LED.DeviceDriverSet_RBGLED_Color(1, is_LightingColorValue_R, is_LightingColorValue_G, is_LightingColorValue_B);
break;
case 4: /*Back*/
AppRBG_LED.DeviceDriverSet_RBGLED_Color(0, is_LightingColorValue_R, is_LightingColorValue_G, is_LightingColorValue_B);
break;
case 5: /*Middle*/
AppRBG_LED.DeviceDriverSet_RBGLED_Color(4, is_LightingColorValue_R, is_LightingColorValue_G, is_LightingColorValue_B);
break;
default:
break;
}
}
/*RBG_LED set*/
void Car::ApplicationFunctionSet_RGB(void)
{
static unsigned long getAnalogue_time = 0;
FastLED.clear(true);
if (true == VoltageDetectionStatus) //Act on low power state?
{
if ((millis() - getAnalogue_time) > 3000)
{
getAnalogue_time = millis();
}
}
unsigned long temp = millis() - getAnalogue_time;
if (valueWithin((temp), 0, 500) && VoltageDetectionStatus == true)
{
switch (temp)
{
case /* constant-expression */ 0 ... 49:
/* code */
AppRBG_LED.DeviceDriverSet_RBGLED_xxx(0 /*Duration*/, 2 /*Traversal_Number*/, CRGB::Red);
break;
case /* constant-expression */ 50 ... 99:
/* code */
AppRBG_LED.DeviceDriverSet_RBGLED_xxx(0 /*Duration*/, 2 /*Traversal_Number*/, CRGB::Black);
break;
case /* constant-expression */ 100 ... 149:
/* code */
AppRBG_LED.DeviceDriverSet_RBGLED_xxx(0 /*Duration*/, 2 /*Traversal_Number*/, CRGB::Red);
break;
case /* constant-expression */ 150 ... 199:
/* code */
AppRBG_LED.DeviceDriverSet_RBGLED_xxx(0 /*Duration*/, 2 /*Traversal_Number*/, CRGB::Black);
break;
case /* constant-expression */ 200 ... 249:
/* code */
AppRBG_LED.DeviceDriverSet_RBGLED_xxx(0 /*Duration*/, 2 /*Traversal_Number*/, CRGB::Red);
break;
case /* constant-expression */ 250 ... 299:
/* code */
AppRBG_LED.DeviceDriverSet_RBGLED_xxx(0 /*Duration*/, 2 /*Traversal_Number*/, CRGB::Red);
break;
case /* constant-expression */ 300 ... 349:
/* code */
AppRBG_LED.DeviceDriverSet_RBGLED_xxx(0 /*Duration*/, 2 /*Traversal_Number*/, CRGB::Black);
break;
case /* constant-expression */ 350 ... 399:
/* code */
AppRBG_LED.DeviceDriverSet_RBGLED_xxx(0 /*Duration*/, 2 /*Traversal_Number*/, CRGB::Red);
break;
case /* constant-expression */ 400 ... 449:
/* code */
AppRBG_LED.DeviceDriverSet_RBGLED_xxx(0 /*Duration*/, 2 /*Traversal_Number*/, CRGB::Black);
break;
case /* constant-expression */ 450 ... 499:
/* code */
AppRBG_LED.DeviceDriverSet_RBGLED_xxx(0 /*Duration*/, 2 /*Traversal_Number*/, CRGB::Red);
break;
default:
break;
}
}
else if (((valueWithin((temp), 500, 3000)) && VoltageDetectionStatus == true) || VoltageDetectionStatus == false)
{
switch (Application_SmartRobotCarxxx0.Functional_Mode) //Act on mode control sequence
{
case /* constant-expression */ Standby_mode:
/* code */
{
if (VoltageDetectionStatus == true)
{
AppRBG_LED.DeviceDriverSet_RBGLED_xxx(0 /*Duration*/, 2 /*Traversal_Number*/, CRGB::Red);
delay(30);
AppRBG_LED.DeviceDriverSet_RBGLED_xxx(0 /*Duration*/, 2 /*Traversal_Number*/, CRGB::Black);
delay(30);
}
else
{
static uint8_t setBrightness = 0;
static boolean et = false;
static unsigned long time = 0;
if ((millis() - time) > 10)
{
time = millis();
if (et == false)
{
setBrightness += 1;
if (setBrightness == 100)
et = true;
}
else if (et == true)
{
setBrightness -= 1;
if (setBrightness == 0)
et = false;
}
}
// AppRBG_LED.leds[1] = CRGB::Blue;
AppRBG_LED.leds[0] = CRGB::Violet;
FastLED.setBrightness(setBrightness);
FastLED.show();
}
}
break;
case /* constant-expression */ CMD_Programming_mode:
/* code */
{
}
break;
case /* constant-expression */ TraceBased_mode:
/* code */
{
AppRBG_LED.DeviceDriverSet_RBGLED_xxx(0 /*Duration*/, 2 /*Traversal_Number*/, CRGB::Green);
}
break;
case /* constant-expression */ ObstacleAvoidance_mode:
/* code */
{
AppRBG_LED.DeviceDriverSet_RBGLED_xxx(0 /*Duration*/, 2 /*Traversal_Number*/, CRGB::Yellow);
}
break;
case /* constant-expression */ Follow_mode:
/* code */
{
AppRBG_LED.DeviceDriverSet_RBGLED_xxx(0 /*Duration*/, 2 /*Traversal_Number*/, CRGB::Blue);
}
break;
case /* constant-expression */ Rocker_mode:
/* code */
{
AppRBG_LED.DeviceDriverSet_RBGLED_xxx(0 /*Duration*/, 2 /*Traversal_Number*/, CRGB::Violet);
}
break;
default:
break;
}
}
}
/*Rocker control mode*/
void Car::ApplicationFunctionSet_Rocker(void)
{
if (Application_SmartRobotCarxxx0.Functional_Mode == Rocker_mode)
{
ApplicationFunctionSet_SmartRobotCarMotionControl(Application_SmartRobotCarxxx0.Motion_Control /*direction*/, Rocker_CarSpeed /*speed*/);
}
}
/*Line tracking mode*/
void Car::Track(void) {
static boolean timestamp = true;
static boolean BlindDetection = true;
static unsigned long MotorRL_time = 0;
if (Car_LeaveTheGround == false) //Check if the car leaves the ground
{
ApplicationFunctionSet_SmartRobotCarMotionControl(stop_it, 0);
return;
}
if ((valueWithin(TrackingData_M, TrackingDetection_S, TrackingDetection_E))&&(valueWithin(TrackingData_R, TrackingDetection_S, TrackingDetection_E)&&(valueWithin(TrackingData_L, TrackingDetection_S, TrackingDetection_E))))
{
/*Achieve straight and uniform speed movement*/
ApplicationFunctionSet_SmartRobotCarMotionControl(stop_it, 0);
unsigned long decoded;
do {
// Try to read semaphore
decode_results IRData;
int semaphoreDetectionAttempts = 10;
int semaphoreAttemptSuccessful = 0;
do {
Serial.print(10-semaphoreDetectionAttempts);
delay(200);
semaphoreAttemptSuccessful = IRReceiver.decode(&IRData);
IRReceiver.resume();
} while(semaphoreAttemptSuccessful == 0 && --semaphoreDetectionAttempts > 0);
if(semaphoreAttemptSuccessful == 0) {
// No semaphore detected.
Serial.println("No semaphore detected.");
break;
}
unsigned long result = IRData.value;
unsigned long oracle = ULONG_MAX >> sizeof(unsigned long) * 4;
decoded = 0;
for(int i = 0; i < sizeof(unsigned long) * 8; ++i) {
decoded |= ((result >> i) & 0x01) << (((sizeof(unsigned long) * 8) - 1) - i);
}
Serial.print("Semaphore state: ");
Serial.print(result, HEX);
Serial.print("/");
Serial.println(decoded, HEX);
} while (decoded != SEMAPHORE_GREEN);
Serial.println("Leaving line");
ApplicationFunctionSet_SmartRobotCarMotionControl(Forward, CAR_CRUISE_SPEED);
delay(400);
} else {
ApplicationFunctionSet_SmartRobotCarMotionControl(Forward, CAR_CRUISE_SPEED);
timestamp = true;
BlindDetection = true;
}
}
void Car::ObstacleAvoidance(void)
{
if(Application_SmartRobotCarxxx0.Functional_Mode != ObstacleAvoidance_mode) {
return;
}
contatore++;
if(contatore > 30){
Serial.println("SONO NEL NOSTROOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOOO");
//checkALato
ApplicationFunctionSet_SmartRobotCarMotionControl(stop_it, 0);
int leftMinDistance = 500;
int leftMinAngolo;
int rightMinDistance = 500;
int rightMinAngolo;
uint16_t get_Distance;
for (uint8_t i = 0; i <= 7; i += 1) //1、3、5 Omnidirectional detection of obstacle avoidance status
{
AppServo.DeviceDriverSet_Servo_control(10 * i /*Position_angle*/);
delayMS(20);
AppULTRASONIC.DeviceDriverSet_ULTRASONIC_Get(&get_Distance /*out*/);
if(get_Distance < leftMinDistance){
leftMinDistance = get_Distance;
leftMinAngolo = i;
}
}
for (uint8_t i = 11; i <= 18; i += 1) //1、3、5 Omnidirectional detection of obstacle avoidance status
{
AppServo.DeviceDriverSet_Servo_control(10 * i /*Position_angle*/);
delayMS(20);
AppULTRASONIC.DeviceDriverSet_ULTRASONIC_Get(&get_Distance /*out*/);
if(get_Distance < rightMinDistance){
rightMinDistance = get_Distance;
rightMinAngolo = i;
}
}
AppServo.DeviceDriverSet_Servo_control(US_ROTATION_INITIAL);
float rapporto = rightMinDistance / leftMinDistance;
if(rapporto > 3){
ApplicationFunctionSet_SmartRobotCarMotionControl(Backward, 70);
delay(350);
if(rapporto>5.5){
ApplicationFunctionSet_SmartRobotCarMotionControl(Left, 70);
delay(300);
}else{
ApplicationFunctionSet_SmartRobotCarMotionControl(LeftForward, 150);
delay(rapporto*30);
}
ApplicationFunctionSet_SmartRobotCarMotionControl(stop_it, 15);
}else if(rapporto < 0.3){
ApplicationFunctionSet_SmartRobotCarMotionControl(Backward, 70);
delay(350);
if(rapporto<0.18){
ApplicationFunctionSet_SmartRobotCarMotionControl(Right, 70);
delay(300);
}else{
ApplicationFunctionSet_SmartRobotCarMotionControl(RightForward, 150);
delay(30/rapporto);
}
ApplicationFunctionSet_SmartRobotCarMotionControl(stop_it, 15);
}
contatore = 0;
}
// Read the distance
uint16_t detectedDistance = 0;
AppULTRASONIC.DeviceDriverSet_ULTRASONIC_Get(&detectedDistance);
Serial.println("sono nel codice di celooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooooo"+detectedDistance);
if(valueWithin(detectedDistance, 0, US_COLLISION_DISTANCE)) {
Serial.println("trovata roba davantiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiiii");
uint16_t maxDistanceValue = 0;
int maxDistanceIndex = -1;
ApplicationFunctionSet_SmartRobotCarMotionControl(stop_it, 0);
for(int step = 0; step <= 180/US_ROTATION_STEP; ++step) {
AppServo.DeviceDriverSet_Servo_control(US_ROTATION_STEP * step);
delayMS(20);
AppULTRASONIC.DeviceDriverSet_ULTRASONIC_Get(&detectedDistance);
Serial.print("[TRY] Angle: ");
Serial.print(step * US_ROTATION_STEP);
Serial.print(" Distance: ");
Serial.println(detectedDistance);
if(!valueWithin(detectedDistance, 0, US_COLLISION_DISTANCE) && detectedDistance >= maxDistanceValue && (abs((US_ROTATION_STEP * step) -90) >= abs((US_ROTATION_STEP * maxDistanceIndex) -90) || maxDistanceIndex == -1)) {
Serial.print("[WIN] Angle: ");
Serial.print(step * US_ROTATION_STEP);
Serial.print(" Distance: ");
Serial.println(detectedDistance);
maxDistanceIndex = step;
maxDistanceValue = detectedDistance;
}
}
AppServo.DeviceDriverSet_Servo_control(US_ROTATION_INITIAL);
if(maxDistanceValue > 0) {
int rotation = (US_ROTATION_STEP * maxDistanceIndex - 90) * -1;
int startingYaw ;
int targetYaw;
float reading;
AppMPU6050getdata.MPU6050_dveGetEulerAngles(&reading);
startingYaw = round(reading) % 360;
if(startingYaw < 0) {
startingYaw = 360 + startingYaw;
}
targetYaw = (startingYaw + rotation) % 360;
if(targetYaw < 0) {
targetYaw = 360 + targetYaw;
}
Serial.print("Current yaw: ");
Serial.println(startingYaw);
Serial.print("Target yaw: ");
SmartRobotCarMotionControl direction;
int distance = 360 - max(startingYaw, targetYaw);
if(distance + min(startingYaw, targetYaw) > 180) {
direction = (startingYaw < targetYaw) ? Right: Left;
} else {
direction = (startingYaw < targetYaw) ? Left: Right;
}
Serial.println(targetYaw);
// Calculate distance between starting point and target point
int targetDistance = max(startingYaw, targetYaw) - min(startingYaw, targetYaw);
if(targetDistance > 180) {
targetDistance = 360 - targetDistance;
}
int currentDistance = targetDistance;
if(rotation != 0) {
do {
ApplicationFunctionSet_SmartRobotCarMotionControl(direction, CAR_TURN_SPEED);
delayMS(CAR_TURN_INTERVAL_MS);
ApplicationFunctionSet_SmartRobotCarMotionControl(stop_it, 0);
// Get distance between current Yaw and starting Yaw (the arc we made)
AppMPU6050getdata.MPU6050_dveGetEulerAngles(&reading);
int currentYaw = round(reading) % 360;
if(currentYaw < 0) {
currentYaw = 360 + currentYaw;
}
currentDistance = max(startingYaw, currentYaw) - min(startingYaw, currentYaw);
if(currentDistance > 180) {
currentDistance = 360 - currentDistance;
}
Serial.print("[LOOP] CurrentYaw: ");
Serial.println(currentYaw);
} while(currentDistance <= targetDistance); // We stop when we made an arc bigger than the arc between start and target points
}
} else {
// Failed to determine a good direction, go backwards
ApplicationFunctionSet_SmartRobotCarMotionControl(Backward, CAR_CRUISE_SPEED);
}
} else {
this->Track();
// ApplicationFunctionSet_SmartRobotCarMotionControl(Forward, CAR_CRUISE_SPEED);
}
}
void Car::Follow(void)
{
static uint16_t ULTRASONIC_Get = 0;
static unsigned long ULTRASONIC_time = 0;
static uint8_t Position_Servo = 1;
static uint8_t timestamp = 3;
static uint8_t OneCycle = 1;
if (Application_SmartRobotCarxxx0.Functional_Mode == Follow_mode)
{
if (Car_LeaveTheGround == false)
{
ApplicationFunctionSet_SmartRobotCarMotionControl(stop_it, 0);
return;
}
AppULTRASONIC.DeviceDriverSet_ULTRASONIC_Get(&ULTRASONIC_Get /*out*/);
if (false == valueWithin(ULTRASONIC_Get, 0, 20)) //There is no obstacle 20 cm ahead?
{
ApplicationFunctionSet_SmartRobotCarMotionControl(stop_it, 0);
static unsigned long time_Servo = 0;
static uint8_t Position_Servo_xx = 0;
if (timestamp == 3)
{
if (Position_Servo_xx != Position_Servo) //Act on servo motor:avoid loop execution
{
Position_Servo_xx = Position_Servo; //Act on servo motor:rotation angle record
if (Position_Servo == 1)
{
time_Servo = millis();
AppServo.DeviceDriverSet_Servo_control(80 /*Position_angle*/);
}
else if (Position_Servo == 2)
{
time_Servo = millis();
AppServo.DeviceDriverSet_Servo_control(20 /*Position_angle*/);
}
else if (Position_Servo == 3)
{
time_Servo = millis();
AppServo.DeviceDriverSet_Servo_control(80 /*Position_angle*/);
}
else if (Position_Servo == 4)
{
time_Servo = millis();
AppServo.DeviceDriverSet_Servo_control(150 /*Position_angle*/);
}
}
}
else
{
if (timestamp == 1)
{
timestamp = 2;
time_Servo = millis();
}
}
if (millis() - time_Servo > 1000) //Act on servo motor:stop at the current location for 2s
{
timestamp = 3;
Position_Servo += 1;
OneCycle += 1;
if (OneCycle > 4)
{
Position_Servo = 1;
OneCycle = 5;
}
}
}
else
{
OneCycle = 1;
timestamp = 1;
if ((Position_Servo == 1))
{ /*Move forward*/
ApplicationFunctionSet_SmartRobotCarMotionControl(Forward, 100);
}
else if ((Position_Servo == 2))
{ /*Turn right*/
ApplicationFunctionSet_SmartRobotCarMotionControl(Right, 150);
}
else if ((Position_Servo == 3))
{
/*Move forward*/
ApplicationFunctionSet_SmartRobotCarMotionControl(Forward, 100);
}
else if ((Position_Servo == 4))
{ /*Turn left*/
ApplicationFunctionSet_SmartRobotCarMotionControl(Left, 150);
}
}
}
else
{
ULTRASONIC_Get = 0;
ULTRASONIC_time = 0;
}
}
/*Servo motor control*/
void Car::ApplicationFunctionSet_Servo(uint8_t Set_Servo)
{
static int z_angle = 9;
static int y_angle = 9;
uint8_t temp_Set_Servo = Set_Servo;
switch (temp_Set_Servo)
{
case 1 ... 2:
{
if (1 == temp_Set_Servo)
{
y_angle -= 1;
}
else if (2 == temp_Set_Servo)
{
y_angle += 1;
}
if (y_angle <= 3) //minimum control
{
y_angle = 3;
}
if (y_angle >= 11) //maximum control
{
y_angle = 11;
}
AppServo.DeviceDriverSet_Servo_controls(/*uint8_t Servo--y*/ 2, /*unsigned int Position_angle*/ y_angle);
}
break;
case 3 ... 4:
{
if (3 == temp_Set_Servo)
{
z_angle += 1;
}
else if (4 == temp_Set_Servo)
{
z_angle -= 1;
}
if (z_angle <= 1) //minimum control
{
z_angle = 1;
}
if (z_angle >= 17) //maximum control
{
z_angle = 17;
}
AppServo.DeviceDriverSet_Servo_controls(/*uint8_t Servo--z*/ 1, /*unsigned int Position_angle*/ z_angle);
}
break;
case 5:
AppServo.DeviceDriverSet_Servo_controls(/*uint8_t Servo--y*/ 2, /*unsigned int Position_angle*/ 9);
AppServo.DeviceDriverSet_Servo_controls(/*uint8_t Servo--z*/ 1, /*unsigned int Position_angle*/ 9);
break;
default:
break;
}
}
/*Standby mode*/
void Car::ApplicationFunctionSet_Standby(void)
{
static bool is_ED = true;
static uint8_t cout = 0;
if (Application_SmartRobotCarxxx0.Functional_Mode == Standby_mode)
{
ApplicationFunctionSet_SmartRobotCarMotionControl(stop_it, 0);
if (true == is_ED) //Used to zero yaw raw data(Make sure the car is placed on a stationary surface!)
{
static unsigned long timestamp; //acquire timestamp
if (millis() - timestamp > 20)
{
timestamp = millis();
if (ApplicationFunctionSet_SmartRobotCarLeaveTheGround() /* condition */)
{
cout += 1;
}
else
{
cout = 0;