-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathGrandChallengeCode.py
1613 lines (1348 loc) · 62 KB
/
GrandChallengeCode.py
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
'''
Program Obejctive: Grand Challenge - ENPM809T - Autonomous Systems
Author: Arshad S.
Version History:
Version - Date - Changes
1.0 - 04/18/2023 - All
2.0 - 07/07/2023 - All
'''
# import necessary packages
import cv2
import os
import glob
import numpy as np
import RPi.GPIO as gpio
from time import sleep
import serial
import math
from picamera.array import PiRGBArray
from picamera import PiCamera
import time
from datetime import datetime
import matplotlib.pyplot as plt
import csv
import imutils
import sys
import smtplib
from smtplib import SMTP
from smtplib import SMTPException
import email
from email.mime.multipart import MIMEMultipart
from email.mime.text import MIMEText
from email.mime.image import MIMEImage
###################################################################
# Function definitions
###################################################################
# Ref: https://www.raspberrypi.com/documentation/accessories/camera.html
class cameraCalculations:
def __init__(self, IMG_WIDTH, IMG_HEIGHT, IMG_COLOR):
self.IMG_WD = IMG_WIDTH
self.IMG_HT = IMG_HEIGHT
self.IMG_CLR = IMG_COLOR
self.FOCAL_LENGTH = 3.04
self.REAL_OBJ_HEIGHT = 57 # in mm
self.REAL_OBJ_WIDTH = 38 # in mm
self.SNSR_HT_PX = IMG_HEIGHT # in px
self.SNSR_HT = 2.7657 # in mm
self.SNSR_WD = 3.68 # in mm
self.HFOV = 62.2
self.VFOV = 48.8
self.CAMERA_TO_IMU_DIST = 95 # in mm
self.CAM_FRM_RATE = 25
self.img_dir_name = 'image_data'
self.img_dir_path = os.path.join(os.path.dirname(os.path.abspath(__file__)), self.img_dir_name)
self.HSV_RED_MIN = [152, 128, 100] # ideal from myhome ambience light : [170, 80, 0]
self.HSV_RED_MAX = [179, 255, 255]
self.HSV_BLU_MIN = [100, 96, 97] # ideal from myhome ambience light : [170, 80, 0]
self.HSV_BLU_MAX = [125, 255, 255]
self.HSV_GRN_MIN = [40, 10, 16] # ideal from myhome ambience light : [170, 80, 0]
self.HSV_GRN_MAX = [96, 255, 230]
self.prevValue = 0
self.DIST_BAND = 10
self.CAMERA_TO_GRPR_DIST = 140
self.CAMERA_TO_GRPROPENING_DIS = 140 # ideal 80
self.blockPickupConfirmRadius = 175
self.blockPickedupRadius = 300
self.K = round((self.REAL_OBJ_WIDTH / self.REAL_OBJ_HEIGHT),3) # ratio of width to height
# print("\nObject Sides Ratio: ", self.K)
def clrImgDir(self):
try:
files = glob.glob(os.path.join(self.img_dir_path, "*.jpg"))
for f in files:
os.remove(f)
except Exception as e:
print("Exception: ", e)
# Function to take a snapshot from RPi
def takeImgRPi(self):
self.clrImgDir()
print("Taking a picture..")
#Define time stamp & record an image
pic_time = datetime.now().strftime("%Y%m%d%H%M%S")
name = pic_time + '.jpg'
command = 'raspistill -w ' + str(self.IMG_WD) + ' -h ' + str(self.IMG_HT) +' -vf -o ' + str(self.img_dir_path) + str('/') + name
# print(command)
os.system(command)
image = cv2.imread(name)
# cv2.imshow(name, image)
# cv2.waitKey(1)
return image
def bandFilter(self, newValue, band):
if newValue >= (self.prevValue + (band / 2)) or newValue <= (self.prevValue - (band / 2)):
output = newValue
else:
output = self.prevValue
self.prevValue = output
return output
def distanceToObject(self, image, x, y, objHtPx):
# Ref: https://www.scantips.com/lights/subjectdistance.html
objHeightOnSensor = (objHtPx / self.SNSR_HT_PX) * self.SNSR_HT
distanceToObject = (self.REAL_OBJ_HEIGHT / objHeightOnSensor) * self.FOCAL_LENGTH
offset = distanceToObject * 0.25
distanceToObject += offset
# distanceToObject = self.bandFilter(distanceToObject, self.DIST_BAND)
cv2.line(image, (int(x), int(y)), (int(self.IMG_WD / 2), int(self.IMG_HT)),(0,0,255),3)
cv2.circle(image, (int(self.IMG_WD/2), int(self.IMG_HT-10)), int(10), (255, 255, 0), -1)
imgText = "Distance: " + str(int(distanceToObject)) + " mm"
fontScale = 1
cv2.putText(image,imgText, (int((self.IMG_WD / 2) - 130), int(self.IMG_HT - 150)), cv2.FONT_HERSHEY_SIMPLEX, fontScale, (0,255,0), 3)
# print("\nDistance to the object: ", distanceToObject)
return image, distanceToObject
def angleToObject(self, image, x, y, radius, distanceToObject):
# Drawing center lines
# cv2.line(image, (int(self.IMG_WD / 2) - 50, int(self.IMG_HT / 2)), (int(self.IMG_WD / 2) + 50, int(self.IMG_HT / 2)),(100,255,100),3)
# cv2.line(image, (int(self.IMG_WD / 2), int(self.IMG_HT / 2) - 50), (int(self.IMG_WD / 2), int(self.IMG_HT / 2) + 50),(100,255,100),3)
cv2.line(image, (int(self.IMG_WD / 2), int(y)), (int(self.IMG_WD / 2), int(self.IMG_HT)),(255, 0, 0),3)
degPerPx = self.HFOV / self.IMG_WD
angleCamera = (int(x) - (self.IMG_WD / 2)) * degPerPx
# mmPerPx = self.SNSR_WD / self.IMG_WD
# opp_side = (abs((self.IMG_WD / 2) - x) * mmPerPx)
# d = opp_side / math.sin(math.radians(angleCamera))
# d = abs(d)
# print("\nd: ", d)
# denominator1 = (d * math.cos(math.radians(angleCamera))) + self.FOCAL_LENGTH + self.CAMERA_TO_IMU_DIST
# numerator1 = d * math.sin(math.radians(angleCamera))
denominator = (distanceToObject * math.cos(math.radians(angleCamera))) + self.FOCAL_LENGTH + self.CAMERA_TO_IMU_DIST
numerator = distanceToObject * math.sin(math.radians(angleCamera))
angleImu = math.atan((numerator / denominator))
angleToObject = round(math.degrees(angleImu), 2)
if angleToObject < 0:
direction = 'Cam Angle: Left '
xCoor = x + radius/2
elif angleToObject > 0:
direction = 'Cam Angle: Right '
xCoor = x - radius/2
else:
direction = 'Cam Angle: Straight '
xCoor = x
# object center to cenetr line
cv2.line(image, (int(xCoor), int(y)), (int(self.IMG_WD / 2), int(y)), (255, 0, 0), 3)
# Angle of the object detected
imgText1 = direction + str(abs(int(angleCamera))) + " deg "
imgText2 = "IMU Angle: "+ str(abs(int(angleToObject))) + " deg"
cv2.putText(image,imgText1, (int((self.IMG_WD / 2) - 130), int(self.IMG_HT - 50)), cv2.FONT_HERSHEY_SIMPLEX, 1, (0, 255, 0), 3)
cv2.putText(image,imgText2, (int((self.IMG_WD / 2) - 130), int(self.IMG_HT - 100)), cv2.FONT_HERSHEY_SIMPLEX, 1, (0, 255, 0), 3)
# print("\n Angle: ", angleToObject, "°")
return angleToObject * 0.75
def detectObject(self, camera, rawCapture):
counterIm = 0
counterNoIm = 0
list_angleToObject = []
list_distanceToObject = []
# Video looping - for each image frame from the video, do the following:
for frame in camera.capture_continuous(rawCapture, format="bgr", use_video_port=False):
x = 0
y = 0
radius = 0
objHtPx = 0
# Read the image frame
image = frame.array
# Convert to BGR image to HSV image
hsvIm = cv2.cvtColor(image, cv2.COLOR_BGR2HSV)
# Define the threshold values for HSV mask (Ref: colorpicker.py)
if self.IMG_CLR == "Green":
minHSV = np.array(self.HSV_GRN_MIN)
maxHSV = np.array(self.HSV_GRN_MAX)
# print("\nMin & Max HSV values: ", minHSV, maxHSV)
elif self.IMG_CLR == "Blue":
minHSV = np.array(self.HSV_BLU_MIN)
maxHSV = np.array(self.HSV_BLU_MAX)
# print("\nMin & Max HSV values: ", minHSV, maxHSV)
elif self.IMG_CLR == "Red":
minHSV = np.array(self.HSV_RED_MIN)
maxHSV = np.array(self.HSV_RED_MAX)
# print("\nMin & Max HSV values: ", minHSV, maxHSV)
else:
minHSV = np.array(self.HSV_RED_MIN)
maxHSV = np.array(self.HSV_RED_MAX)
# print("\nMin & Max HSV values: ", minHSV, maxHSV)
# Create a mask
maskHSV = cv2.inRange(hsvIm, minHSV, maxHSV)
# Blur the masked image before detecting the corners
blurIm_unflt = cv2.GaussianBlur(maskHSV,(3,3),0)
# Apply erosion to remove white noise and dilate to remove black noise
kernel = np.ones((5,5), np.uint8)
blurIm = cv2.erode(blurIm_unflt, kernel, iterations=1)
blurIm = cv2.erode(blurIm_unflt, kernel, iterations=1)
# blurIm = cv2.dilate(blurIm, kernel, iterations=1)
# Detect the top 5 corners using the cv2.goodFeaturesToTrack()
# The top 2 corners will always be two most narrowed corners of the arrow head
quality = 0.1 # varies from 0 to 1; close to 0 implies that even a slight corners are detected
corners = cv2.goodFeaturesToTrack(blurIm,2,quality,10)
len_corners = 0
# Display all types of processed images from Camera Feed - [Original - HSV - Masked - Blurred]
cv2.namedWindow("Camera Feed: Mask - Processed Frame", cv2.WINDOW_NORMAL)
# print('\nShape: maskHSV, blurIm', np.shape(maskHSV), np.shape(blurIm))
cv2.imshow("Camera Feed: Mask - Processed Frame", np.hstack([maskHSV, blurIm]))
cv2.resizeWindow("Camera Feed: Mask - Processed Frame", 640, 480)
#Creating a opencv window - RGB video
cv2.namedWindow('RGB Capture', cv2.WINDOW_NORMAL)
cv2.resizeWindow('RGB Capture', 640, 480)
if isinstance(corners, type(None)):
# print("\n Corners detected: ", len_corners)
# Check key to break from the loop
key = cv2.waitKey(1) & 0xFF
# press the 'q' key to exit
if key == ord("q"):
break
else:
# print("\n Corners detected: ", len(corners))
len_corners = len(corners)
# Get the corners date to find the mid point of the arrow head
if len_corners > 0 :
#find the contour of the arrow
(cont, _) = cv2.findContours(blurIm.copy(), cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)
# Sort the contours from contours with larger areas to smaller areas
cont = sorted(cont, key = lambda x: cv2.contourArea(x), reverse=True)
# when the contour is detected, draw a enclosing circle, line from center of the circle to
# calculate orinetation of the arraow, display it on the image
if (len(cont[0]) > 10): # Contour with larger area, is our contour-of-interest (observed values: > 200, especially when near 30 cm)
# print('\n Length of the contour1: ', len(cont[0]))
# Find the minimum enclosing circle for the biggest contour
(x,y), radius = cv2.minEnclosingCircle(cont[0])
# print("\n [inside]Origin: ", (x,y), "radius:", radius)
# Draw a larger circle - minimum enclosing circle of the contour
cv2.circle(image, (int(x), int(y)), int(radius), (0, 0, 255), 3)
cv2.circle(image, (int(x), int(y)), int(10), (255, 255, 0), -1)
# Drawing lines - Minimum Enclosing Circle height
# cv2.line(image, (int(x),int(y-radius)), (int(x),int(y+radius)),(255,255,0),3)
objHtPx = (2 * radius) / math.sqrt((1 + self.K ** 2))
# Drawing lines - Object height
# cv2.line(image, (int(x+ (radius/2)),int(y-(objHtPx/2))), (int(x+(radius/2)),int(y+(objHtPx/2))),(255,255,0),3)
cv2.line(image, (int(x),int(y-(objHtPx/2))), (int(x),int(y+(objHtPx/2))), (255,255,0),3)
cv2.line(image, (int(x - (radius/2)),int(y)), (int(x + (radius/2)), int(y)), (255,255,0),3)
# print("\n Diameter & Object Height (px): ", (2 * radius), objHtPx)
image, distanceToObject = self.distanceToObject(image, int(x), int(y), objHtPx)
angleToObject = self.angleToObject(image, int(x), int(y), radius, distanceToObject)
list_distanceToObject.append(distanceToObject)
list_angleToObject.append(angleToObject)
counterIm += 1
# print("\n counterIm", counterIm)
cv2.imshow('RGB Capture', image)
else:
print("\n\tNo Block Found!")
counterNoIm += 1
# clear the stream in preparation for the next frame
rawCapture.truncate(0)
# Check key to break from the loop
cv2.waitKey(1)
# press the 'q' key to exit
if counterIm >= 3:
distanceToObject = np.mean(np.array(list_distanceToObject))
angleToObject = np.mean(np.array(list_angleToObject))
break
# press the 'q' key to exit
if counterNoIm >= 3:
distanceToObject = 0
angleToObject = 0
x = 0
y = 0
radius = 0
break
return image, int(x), int(y), radius, objHtPx, round((distanceToObject), 2), angleToObject
###################################################################
###################################################################
class moveNgrab:
def __init__(self):
self.HOP_DIST = 300
self.LAST_MILE_DIST = 300
self.WH_RADIUS = 32.25
# def init(self):
#### Initialize gpio pins ####
###################################################################
def gameover(self):
gpio.output(31, False)
gpio.output(33, False)
gpio.output(35, False)
gpio.output(37, False)
gpio.cleanup()
###################################################################
# Function to rotate servo to the required position (takes 2 seconds)
def ServoControl(self, pos):
if pos == "full_closed":
duty_cycle = 3.5
pwmS.ChangeDutyCycle(duty_cycle)
time.sleep(2)
elif pos == "pickup":
duty_cycle = 3.8
pwmS.ChangeDutyCycle(duty_cycle)
time.sleep(2)
elif pos == "partial_open":
duty_cycle = 5.5
pwmS.ChangeDutyCycle(duty_cycle)
time.sleep(2)
elif pos == "full_open":
duty_cycle = 7.5
pwmS.ChangeDutyCycle(duty_cycle)
time.sleep(2)
else:
duty_cycle = 3.3
pwmS.ChangeDutyCycle(duty_cycle)
time.sleep(2)
return duty_cycle
###################################################################
def ReadIMUx(self, ser):
while True:
if (ser.in_waiting > 0):
line = ser.readline()
line = line.rstrip().lstrip()
line = str(line)
line = line.strip("'")
line = line.strip("b'")
line = line.strip("X: ")
imu_x = float(line)
break
return imu_x
##################################################################
###################################################################
def forward(self, distance, ser):
list_enFL = []
list_enBR = []
list_dist = []
wh_rev = distance * ( 1 / (2 * math.pi * (self.WH_RADIUS)) ) # prev ideal value = 0.03625
wh_stop = int(960 * wh_rev)
counterBR = np.uint64(0)
counterFL = np.uint64(0)
buttonBR = int(0)
buttonFL = int(0)
# Initialize pwmm signal to control motor
# pwm3 = gpio.PWM(33, 50) # to control right wheels
# pwm2 = gpio.PWM(35, 50) # to control left wheels
val = 60
pwm3.start(val)
pwm2.start(val)
time.sleep(0.1)
while True:
# counting the encoder pulses BR
if int(gpio.input(12)) != int(buttonBR):
buttonBR = int(gpio.input(12))
counterBR += 1
# counting the encoder pulses
if int(gpio.input(7)) != int(buttonFL):
buttonFL = int(gpio.input(7))
counterFL += 1
#PROPORTIONAL CONTROLLER
err = counterFL - counterBR
# print("Error", err)
kp = 2.0
if err < 0:
if (val + (-err*kp)) > 10 and (val + (-err*kp)) < 90:
pwm2.ChangeDutyCycle(val + (-err*kp))
#time.sleep(0.1)
else:
print("Max dutycycle reached!")
elif err>=0:
if (val - (err*kp)) > 10 and (val - (err*kp)) < 90:
pwm2.ChangeDutyCycle(val - (err*kp))
#time.sleep(0.1)
else:
print("Min dutycycle reached!")
# stopping the counter when the value reaches some point
if counterFL >= wh_stop:
pwm3.stop()
pwm2.stop()
break
# stopping the counter when the value reaches some point
if counterBR >= wh_stop:
pwm2.stop()
pwm3.stop()
break
list_enFL.append(counterFL)
list_enBR.append(counterBR)
return (counterFL, counterBR)
###################################################################
def reverse(self, distance, ser):
list_enFL = []
list_enBR = []
list_dist = []
wh_rev = distance * ( 1 / (2 * math.pi * (self.WH_RADIUS)) ) # prev ideal value = 0.03625
wh_stop = int(960 * wh_rev)
counterBR = np.uint64(0)
counterFL = np.uint64(0)
buttonBR = int(0)
buttonFL = int(0)
# Initialize pwmm signal to control motor
val = 60
pwm1.start(val)
pwm4.start(val)
time.sleep(0.1)
while True:
# counting the encoder pulses BR
if int(gpio.input(12)) != int(buttonBR):
buttonBR = int(gpio.input(12))
counterBR += 1
# counting the encoder pulses
if int(gpio.input(7)) != int(buttonFL):
buttonFL = int(gpio.input(7))
counterFL += 1
#PROPORTIONAL CONTROLLER
err = counterFL - counterBR
kp = 2.0
if err < 0:
if (val + (-err*kp)) > 10 and (val + (-err*kp)) < 90:
pwm1.ChangeDutyCycle(val + (-err*kp))
#time.sleep(0.1)
else:
print("Max dutycycle reached!")
elif err>=0:
if (val - (err*kp)) > 10 and (val - (err*kp)) < 90:
pwm1.ChangeDutyCycle(val - (err*kp))
#time.sleep(0.1)
else:
print("Min dutycycle reached!")
# stopping the counter when the value reaches some point
if counterFL >= wh_stop:
pwm1.stop()
pwm4.stop()
break
# stopping the counter when the value reaches some point
if counterBR >= wh_stop:
pwm1.stop()
pwm4.stop()
break
list_enFL.append(counterFL)
list_enBR.append(counterBR)
return (counterFL, counterBR)
###################################################################
def left(self, val):
counterBR = np.uint64(0)
counterFL = np.uint64(0)
buttonBR = int(0)
buttonFL = int(0)
# Initialize pwmm signal to control motor
pwm3.start(val)
pwm1.start(val)
time.sleep(0.1)
###################################################################
def right(self, val):
counterBR = np.uint64(0)
counterFL = np.uint64(0)
buttonBR = int(0)
buttonFL = int(0)
# Initialize pwmm signal to control motor
pwm2.start(val)
pwm4.start(val)
time.sleep(0.1)
###################################################################
def anglePerioidicity(self, angle):# converts the angles from 0 to 360 to -180 to 180
angle = angle % 360
if angle > 180:
angle = angle - 360
else:
angle = angle
return angle
###################################################################
class obstacleAvoidance():
def __init__(self):
self.RBT_TO_SNR_OFST = 20
self.SNR_TO_GRPR_OFST = 150
self.SAFE_DIST = (304 + 100 + 50 + self.SNR_TO_GRPR_OFST) # 1 Ft + gripper distance
# Function to calculate instantaneous distance
def distance(self):
# Generate trigger pulse
gpio.output(trig, True)
time.sleep(0.00001)
gpio.output(trig, False)
# Generate echo time signal
while gpio.input(echo) == 0:
pulse_start = time.time()
while gpio.input(echo) == 1:
pulse_end = time.time()
pulse_duration = pulse_end - pulse_start
# Convert time to distance
distance = pulse_duration * 17150
distance = round(distance, 2)
return ((distance * 10) + self.RBT_TO_SNR_OFST) # returning in mm
# Function to calculate average distance (takes 2 seconds)
def AvgDistance(self, num_of_readings):
obstSafeDist = False
average_dist = np.array([])
distances = []
for i in range(num_of_readings):
inst_val = self.distance()
#print("Distance: ", inst_val, "mm")
distances.append(inst_val)
time.sleep(0.01)
avg_dist = round(np.average(distances),2)
# print("Average distance to the obstacle: ",avg_dist," mm")
if avg_dist <= self.SAFE_DIST:
obstSafeDist = True
return avg_dist, obstSafeDist
###################################################################
class email_smtp:
def __init__(self) -> None:
#Email information
self.smtpUser = '[email protected]'
self.smtpPass = 'ksveygscusrwlfld'
self.toAdd = '[email protected]'
self.cc = '[email protected]'
self.fromAdd = self.smtpUser
self.mail_directory = os.path.join(os.path.dirname(os.path.abspath(__file__)), 'image_data')
def clear_mail_dir(self):
try:
files = glob.glob(os.path.join(self.mail_directory, "*.jpg"))
for f in files:
os.remove(f)
except Exception as e:
print(e)
def mail_snapshot(self, subject, pic_time):
try:
#Destination email information
msg = MIMEMultipart()
msg['Subject'] = subject
msg['From'] = self.fromAdd
msg['To'] = self.toAdd
msg['cc'] = self.cc
msg.preamble = "Attached Image recorded at "+ pic_time
#Email text
body = MIMEText('Attached Image recorded at '+ pic_time)
msg.attach(body)
#Attach Image
fp = open(str(self.mail_directory) + str('/')+ pic_time + '.jpg', 'rb')
img = MIMEImage(fp.read())
img.add_header('Content-Disposition', "attachment; filename= %s" % "snapshot.jpg")
fp.close()
msg.attach(img)
#Send email
s = smtplib.SMTP('smtp.gmail.com', 587)
s.ehlo()
s.starttls()
s.ehlo()
s.login(self.smtpUser, self.smtpPass)
s.sendmail(self.fromAdd, [self.toAdd, self.cc], msg.as_string())
s.quit()
except Exception as e:
print("Email delivery failed!")
print(e)
################## Define Class Ojects ################################
cr = cameraCalculations(IMG_WIDTH=1280, IMG_HEIGHT=720, IMG_COLOR="Red")
cg = cameraCalculations(IMG_WIDTH=1280, IMG_HEIGHT=720, IMG_COLOR="Green")
cb = cameraCalculations(IMG_WIDTH=1280, IMG_HEIGHT=720, IMG_COLOR="Blue")
ca = obstacleAvoidance()
mg = moveNgrab()
em = email_smtp()
############################ Start of Initializationns #####################################
pwrSwitch = bool(int(input("\nPower Switch is ON?(0/1)")))
# initialization: Motors & Encoders
gpio.setmode(gpio.BOARD)
gpio.setup(31, gpio.OUT) # IN4
gpio.setup(33, gpio.OUT) # IN3
gpio.setup(35, gpio.OUT) # IN2
gpio.setup(37, gpio.OUT) # IN1
gpio.setup(7, gpio.IN, pull_up_down = gpio.PUD_UP)
gpio.setup(12, gpio.IN, pull_up_down = gpio.PUD_UP)
# Servo Control - Define pin allocations
gpio.setup(36, gpio.OUT)
# Distance Measurement - Define pin allocations
trig = 16
echo = 18
gpio.setup(trig, gpio.OUT)
gpio.setup(echo, gpio.IN)
######################################################
# Motor Control - Initialize PWM
pwm3 = gpio.PWM(33, 50) # to control right wheels
pwm1 = gpio.PWM(37, 50) # to control left wheels
pwm2 = gpio.PWM(35, 50) # to control left wheels
pwm4 = gpio.PWM(31, 50) # to control right wheels
# Servo Control - Initialize PWM
pwmS = gpio.PWM(36, 50)
pwmS.start(5)
# Sonar - Initialize - Ensure output has no value
gpio.output(trig, False)
time.sleep(0.01)
# Camera - Initialize #############
# initialize Camera
camera = PiCamera()
camera.resolution = (cr.IMG_WD, cr.IMG_HT)
camera.framerate = cr.CAM_FRM_RATE
camera.vflip = True
camera.hflip = True
rawCapture = PiRGBArray(camera, size=(cr.IMG_WD, cr.IMG_HT))
# allow the camera to warmup
time.sleep(0.1)
#######
# img, x, y, radius, objHtPx, distanceToObject, angleToObject = cr.detectObject(camera, rawCapture)
# print("\n Origin: ", (x,y), "\n radius:", radius, "\n Object Height (px): ", objHtPx, "\n Distance to Object: ", distanceToObject, "\n Angle to Object: ", angleToObject)
# cameraOK = input("Camera OK? (Y/N) ")
# print("\n[test] Camera: ", cameraOK)
# %% IMU - Initialize - Identify serial connection
ser = serial.Serial('/dev/ttyUSB0', 9600)
countImu = 0
imu_x = 0
while True:
if (ser.in_waiting > 0):
countImu += 1
line = ser.readline()
if countImu > 10:
# Read serial stream and remove unnecessary characters
line = line.rstrip().lstrip()
line = str(line)
line = line.strip("'")
line = line.strip("b'")
line = line.strip("X: ")
imu_x = float(line)
# print(imu_x, "\n")
break
time.sleep(0.5)
print("\n[test] IMU: ", imu_x)
# Calculate the 1st avg. obstacle distance of an object (4 samples - lessthan 1 seconds)
avgObsDist, safeDistFlg = ca.AvgDistance(4)
print("\n[test] Sonar: ", avgObsDist, "\tSafe Distance Flag: ", safeDistFlg)
# Move the gripper to Full- Closed position (2 sec)
print("Moving the gripper to full-closed position")
duty = mg.ServoControl("full_closed")
############################ End of Initializationns #####################################
list_x = []
list_y = []
list_angle = []
global cur_x
cur_x = 0
countercheckNdrop = 0
imgNum = 1
f = open('encodertrajectory.txt','a')
em.clear_mail_dir()
##################### End of main initializations #######################################
def blockTransportEmail(objClr):
print("\n########## Starting to send the email ##########")
global imgNum
img, _, _, _, radius, _, _ = objClr.detectObject(camera, rawCapture)
#
# objClr.clrImgDir()
# Define time stamp & record an image
pic_time = datetime.now().strftime("%Y%m%d%H%M%S")
name = pic_time + '.jpg'
imgText = "Block-" + str(imgNum) + "/6"
cv2.putText(img,imgText, (int((objClr.IMG_WD) - 200), int(40)), cv2.FONT_HERSHEY_SIMPLEX, 1, (0, 0, 255), 3)
cv2.imwrite(str(objClr.img_dir_path) + str('/') + name, img)
time.sleep(2)
em.mail_snapshot("Block" + str(imgNum) + " Pickedup Message!", pic_time)
imgNum += 1
time.sleep(1)
print("\n\tSent the email")
##################### End of blockTransportEmail function #######################################
def turnAngleRequired(forNearDistance, objClr):
print("\n\tturnAngleRequired(forNearDistance, objClr)")
noBlockFound = False
if forNearDistance == True:
AngleTolerance = 2
else:
AngleTolerance = 2
_, _, _, radius, _, _, angleToObject = objClr.detectObject(camera, rawCapture)
angle_desired = angleToObject
cur_x_mod = mg.anglePerioidicity(mg.ReadIMUx(ser))
new_x = cur_x_mod
val = 70
if angle_desired < -2:
print("\n\tLeft turn inititated!")
mg.left(val)
while True:
new_x = mg.anglePerioidicity(mg.ReadIMUx(ser))
diff = abs(cur_x_mod - new_x)
if (abs(cur_x_mod - new_x) >= abs(angle_desired) - AngleTolerance): # -2 is for inertia
print("\n\tThe difference between current angle and new angle: ", diff)
pwm3.stop(val)
pwm1.stop(val)
time.sleep(1)
break
elif angle_desired > 2:
print("\n\tRight turn inititated!")
mg.right(val)
while True:
new_x = mg.anglePerioidicity(mg.ReadIMUx(ser))
diff = abs(cur_x_mod - new_x)
if (abs(cur_x_mod - new_x) >= abs(angle_desired) - AngleTolerance): # -2 is for inertia
print("\n\tThe difference between current angle and new angle: ", diff)
pwm2.stop(val)
pwm4.stop(val)
time.sleep(1)
# gameover()
break
else:
pass
# print("No turn left or right!")
time.sleep(1)
print("\n\tradius detected: ", radius)
# cv2.waitKey(0)
if radius < 2:
print("\n\tradius detected: ", radius)
print("\n\tBlock not found (may be toppled/ missed/not visible), coming out of descentAction!")
noBlockFound = True
# print("\n\tcoming out of turnAngleRequired")
return noBlockFound
############################ End of turnAngleRequired function #####################################
def headingTurn(angle_tobeRotated):
print("\n########## headingTurn(angle_tobeRotated) ##########")
AngleTolerance = 2
headingTurnFlag = False
cur_x = mg.ReadIMUx(ser)
# calcualte the smaller of the angle difference and find out which side is that smaller angle
angle_desired = angle_tobeRotated - cur_x
angle_desired = angle_desired - 360*math.floor(0.5 + (angle_desired/ 360))
print("\n\tangle_desired: ", angle_desired)
val = 60
if angle_desired < 0:
print("\n\tLeft turn inititated!")
mg.left(val)
while True:
# keep on sensing new IMU angle, find out difference (smaller one)
# with needed IMU angle, rotate until difference is within tolerance.
# -2 is to account for inertia of rotation
new_x = mg.ReadIMUx(ser)
diff = (angle_tobeRotated - new_x)
diff = diff - 360*math.floor(0.5 + (diff/ 360))
if (abs(diff) <= AngleTolerance): # -2 is for inertia
pwm3.stop(val)
pwm1.stop(val)
time.sleep(1)
cur_x = mg.ReadIMUx(ser)
# print("\n Current Heading: ", cur_x)
headingTurnFlag = True
break
elif angle_desired > 0:
print("\n\tRight turn inititated!")
mg.right(val)
while True:
new_x = mg.ReadIMUx(ser)
diff = (angle_tobeRotated - new_x)
diff = diff - 360*math.floor(0.5 + (diff/ 360))
if (abs(diff) <= AngleTolerance): # -2 is for inertia
pwm2.stop(val)
pwm4.stop(val)
time.sleep(1)
cur_x = mg.ReadIMUx(ser)
# print("\n\tCurrent Heading: ", cur_x)
headingTurnFlag = True
# gameover()
break
else:
headingTurnFlag = True
pass
# print("No turn left or right!")
return headingTurnFlag
############################ End of headingTurn function #####################################
def reachBlock(objClr):
print("\n########## reachBlock(objClr) ##########")
img, x, y, radius, objHtPx, distanceToObject, angleToObject = objClr.detectObject(camera, rawCapture)
distance = distanceToObject - objClr.CAMERA_TO_GRPROPENING_DIS
print("\n\tReachingBlock Distance: ", distance)
###########################################################
if distance > (1000):
print("\n\tReachBlock Distance found as > 1000, which is :", distance)
# hops = int((distance) / mg.HOP_DIST)
# print("\nNumber of hops: ", hops)
countReachBlock = 1
while distance > 1000:
# Move forward in hops
print("\n\tMoving until distance is < 1000 , ", "\n\tCounter: ", countReachBlock, "\n\tMoving distance: ", (distance / 2))
flTicks, brTicks= mg.forward((distance / 2), ser)
cur_x = mg.ReadIMUx(ser)
dActual = ((flTicks + brTicks) / 2) * (2 * math.pi * mg.WH_RADIUS) / 960
x_coor = round(dActual * math.sin(math.radians(cur_x)), 3)
y_coor = round(dActual * math.cos(math.radians(cur_x)), 3)
list_x.append(x_coor)
list_y.append(y_coor)
list_angle.append(cur_x)
time.sleep(1)
#
noBlk = turnAngleRequired(forNearDistance=False, objClr=objClr)
#
img, x, y, radius, objHtPx, distanceToObject, angleToObject = objClr.detectObject(camera, rawCapture)
distance = distanceToObject - objClr.CAMERA_TO_GRPROPENING_DIS
print("\n\tNew distance after moving: ", distance)
#
countReachBlock += 1
print("\n\tCompleted ReachBLock distance!!")
print("\n\tnNow the distance shall be: 501 < distance <= 1000")
print("\n\tNew distance after completing ReachBlock: ", distance)
############################ End of reachBlock function #####################################
def descentAction(objClr):
print("\n########## descentAction(objClr) ##########")
# Turn angle - required
noBlk = turnAngleRequired(forNearDistance=True, objClr=objClr)
############## Now calculate distance and divide it in 6 parts
_, _, _, radius, _, distanceToObject, angleToObject = objClr.detectObject(camera, rawCapture)
distance = distanceToObject - objClr.CAMERA_TO_GRPROPENING_DIS
print("\n\tdescentAction distance calculated is: ", distance)
descentDist = int(distance / 6)
print("\n\tdescending by step-distance: ", descentDist)
counterDescent = 1
permissibleAngle = 2
while radius > 5:
print("\n\tTravelling descent - " + str(counterDescent) + "/6", descentDist)
flTicks, brTicks= mg.forward(descentDist, ser)
_, _, _, radius, _, _, angleToObject = objClr.detectObject(camera, rawCapture)
angle_desired = angleToObject
cur_x_mod = mg.anglePerioidicity(mg.ReadIMUx(ser))
new_x = cur_x
val = 50
if angle_desired < - permissibleAngle:
mg.left(val)
while True:
new_x = mg.anglePerioidicity(mg.ReadIMUx(ser))
if (abs(cur_x_mod - new_x) >= abs(angle_desired)):
pwm3.stop(val)
pwm1.stop(val)
time.sleep(1)
break
elif angle_desired > permissibleAngle:
mg.right(val)
while True:
new_x = mg.ReadIMUx(ser)
new_x = mg.anglePerioidicity(new_x)
if (abs(cur_x_mod - new_x) >= abs(angle_desired)):
pwm2.stop(val)
pwm4.stop(val)
time.sleep(1)
break
else:
pass
# print("\nradius after step ", counterDescent, ": ", radius)
if counterDescent == 2:
permissibleAngle = 1
print("\n\tPreposing gripper for picking up!")
duty = mg.ServoControl("full_open")
if counterDescent == 5: