-
Notifications
You must be signed in to change notification settings - Fork 0
/
Copy pathall_together_trap_bridge_stairs_lab_changed.py
2389 lines (2169 loc) · 105 KB
/
all_together_trap_bridge_stairs_lab_changed.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
#!/usr/bin/python3
# -*- coding: utf-8 -*-
import cv2
import cv2 as cv
import numpy as np
import time
import threading
import math
import RobotControl.Serial_Servo_Running as SSR
import signal
#import PWMServo
import copy
from CameraCalibration.CalibrationConfig import *
# from cross_trap_mine_2 import go
############################### calibration #######################
# 加载参数
param_data = np.load(calibration_param_path + '.npz')
# 获取参数
dim = tuple(param_data['dim_array'])
k = np.array(param_data['k_array'].tolist())
d = np.array(param_data['d_array'].tolist())
print('加载参数完成')
print('dim:\n', dim)
print('k:\n', k)
print('d:\n', d)
# 截取区域,1表示完全截取
scale = 1
# 优化内参和畸变参数
p = cv2.fisheye.estimateNewCameraMatrixForUndistortRectify(k, d, dim, None)
Knew = p.copy()
if scale: # change fov
Knew[(0, 1), (0, 1)] = scale * Knew[(0, 1), (0, 1)]
map1, map2 = cv2.fisheye.initUndistortRectifyMap(k, d, np.eye(3), Knew, dim, cv2.CV_16SC2)
color_range = {'yellow_door': [(10, 43, 46), (34, 255, 255)],
'red_floor1': [(0, 43, 46), (10, 255, 255)],
'red_floor2': [(156, 43, 46), (180, 255, 255)],
'green_bridge': [(35, 43, 20), (100, 255, 255)],
'yellow_hole': [(10, 70, 46), (34, 255, 255)],
'black_hole': [(0, 0, 0), (180, 255, 80)],
'black_gap': [(0, 0, 0), (180, 255, 100)],
'black_dir': [(0, 0, 0), (180, 255, 46)],
# 'blue': [(110, 43, 46), (124, 255, 255)],
'blue': [(95, 43, 90), (130, 255, 255)],
'black_door': [(0, 0, 0), (180, 255, 46)],
'white': [(0, 0, 160), (180, 30, 255)]
}
color_dict = {'red': {'Lower': np.array([0, 60, 60]), 'Upper': np.array([6, 255, 255])},
'blue': {'Lower': np.array([100, 80, 46]), 'Upper': np.array([124, 255, 255])},
# [(110, 43, 46), (124, 255, 255)]
'green': {'Lower': np.array([35, 43, 46]), 'Upper': np.array([77, 255, 255])},
'yellow_door': {'Lower': np.array([10, 43, 46]), 'Upper': np.array([34, 255, 255])},
'black': {'Lower': np.array([0, 0, 0]), 'Upper': np.array([180, 255, 46])},
'black_obstacle': {'Lower': np.array([0, 0, 0]), 'Upper': np.array([180, 255, 90])},
'black_dir': {'Lower': np.array([0, 0, 0]), 'Upper': np.array([180, 255, 46])}
}
lab_range = {
# 'yellow_door': [(11, 63, 66), (34, 255, 255)],
# 'black_door': [(0, 0, 0), (80, 255, 5)],
#
# 'blue': [(0, 0, 0), (255, 175, 94)], # dark blue
# 'blue_bridge': [(137, 93, 0), (255, 122, 121)], # light blue
#
# 'red': [(0, 154, 130), (255, 255, 255)],
#
# 'green_bridge': [(47, 0, 135), (255, 110, 255)],
# 'black_hole': [(0, 0, 0), (180, 255, 80)],
# 'black_gap': [(0, 0, 0), (180, 255, 100)],
# 'black_dir': [(0, 0, 0), (180, 255, 46)],
# 'blue_old': [(0, 92, 52), (255, 178, 111)],
# 'blue_floor' : [(0, 0, 0), (255, 154, 102)],
# 'white': [(215, 0, 0), (255, 255, 255)],
'red': [(0, 154, 130), (255, 255, 255)],
'green': [(47, 0, 125), (255, 110, 255)],
'blue': [(0, 0, 0), (255, 175, 104)],#94
'yellow': [(11, 63, 66), (34, 255, 255)],
'white': [(215, 0, 0), (255, 255, 255)],
'black': [(0, 0, 0), (50, 255, 255)]
}
lab_red = [(0, 154, 130), (255, 255, 255)]
########################## 参数设置 ##########################
# video = "orgin_video.mp4"
# cap = cv2.VideoCapture(video)
cap = cv2.VideoCapture(-1)
Running = True
org_img = None # 全局变量,原始图像
ret = False # 读取图像标志位
debug = True
key = -1 # waitKey
isstop = True
# level2 parameters
step = 1
# ret = False
move_count = 0
forward_count = 0 # cross mine
end = 0
door_cnt = 0
door_end = 0
r_w = 640
r_h = 480
# should_chose = False
blue_persent = 0
################################################读取图像线程#################################################
def get_img():
global cap, org_img, Running, debug, key, ret
while True:
if cap.isOpened():
ret, org_img_fish = cap.read()
# org_img = cv2.remap(org_img_fish.copy(), map1, map2, interpolation=cv2.INTER_LINEAR, borderMode=cv2.BORDER_CONSTANT)
if ret:
org_img = cv2.remap(org_img_fish.copy(), map1, map2, interpolation=cv2.INTER_LINEAR,
borderMode=cv2.BORDER_CONSTANT)
if not debug:
# cv2.imshow('orginal frame', org_img)
# time.sleep(0.5)
time.sleep(0.6)
key = cv2.waitKey(3)
else:
time.sleep(0.01)
else:
time.sleep(0.01)
# 读取图像线程
th1 = threading.Thread(target=get_img)
th1.setDaemon(True) # 设置为后台线程,这里默认是False,设置为True之后则主线程不用等待子线程
th1.start()
########################## 控制线程 ##########################
SSR.start_action_thread()
# SSR.change_action_value("1",0) # 静止
########################## 必要函数 ##########################
# 得到最大轮廓和对应的最大面积
def getAreaMaxContour(contours, area_min=4000):
contour_area_temp = 0
contour_area_max = 0
area_max_contour = None
# area_max_contour = np.array([[[0, 0]], [[0, 1]], [[1, 1]], [[1, 0]]])
for c in contours: # 遍历所有轮廓
contour_area_temp = math.fabs(cv2.contourArea(c)) # 计算轮廓面积
if contour_area_temp > contour_area_max:
contour_area_max = contour_area_temp
if contour_area_temp > area_min: # 只有在面积大于 area_min 时,最大面积的轮廓才是有效的,以过滤干扰
area_max_contour = c
return area_max_contour, contour_area_max # 返回最大的轮廓
def getAreaSecondMaxContour(contours, max_area):
contour_area_temp = 0
contour_area_max = 0
area_max_contour = None
# area_max_contour = np.array([[[0, 0]], [[0, 1]], [[1, 1]], [[1, 0]]])
for c in contours: # 历遍所有轮廓
contour_area_temp = math.fabs(cv2.contourArea(c)) # 计算轮廓面积
if max_area == contour_area_temp:
continue
elif contour_area_temp > contour_area_max:
contour_area_max = contour_area_temp
if contour_area_temp > 1500: # 只有在面积大于4000时,最大面积的轮廓才是有效的,以过滤干扰
area_max_contour = c
return area_max_contour, contour_area_max # 返回最大的轮廓
def getLineSumContour(contours, area=1):
contours_sum = None
for c in contours:
area_temp = math.fabs(cv2.contourArea(c))
rect = cv2.minAreaRect(c) # 最小外接矩形
box = np.int0(cv2.boxPoints(rect)) # 最小外接矩形的四个顶点 int0 <=> int64
edge1 = math.sqrt(math.pow(box[3, 1] - box[0, 1], 2) + math.pow(box[3, 0] - box[0, 0], 2))
edge2 = math.sqrt(math.pow(box[3, 1] - box[2, 1], 2) + math.pow(box[3, 0] - box[2, 0], 2))
ratio = edge1 / edge2
if (area_temp > area) and (ratio > 3 or ratio < 0.33):
contours_sum = c
break
for c in contours:
area_temp = math.fabs(cv2.contourArea(c))
rect = cv2.minAreaRect(c) # 最小外接矩形
box = np.int0(cv2.boxPoints(rect)) # 最小外接矩形的四个顶点 int0 <=> int64
edge1 = math.sqrt(math.pow(box[3, 1] - box[0, 1], 2) + math.pow(box[3, 0] - box[0, 0], 2))
edge2 = math.sqrt(math.pow(box[3, 1] - box[2, 1], 2) + math.pow(box[3, 0] - box[2, 0], 2))
ratio = edge1 / edge2
if (area_temp > area) and (ratio > 3 or ratio < 0.33):
contours_sum = np.concatenate((contours_sum, c), axis=0) # 将所有轮廓点拼接到一起
return contours_sum
# 得到全部的总的轮廓
def getSumContour(contours, area=1):
contours_sum = None
for c in contours:
area_temp = math.fabs(cv2.contourArea(c))
if (area_temp > area):
contours_sum = c
break
for c in contours:
area_temp = math.fabs(cv2.contourArea(c))
if (area_temp > area):
contours_sum = np.concatenate((contours_sum, c), axis=0) # 将所有轮廓点拼接到一起
return contours_sum
def direction_only_angle(resize_width, resize_height):
global org_img, reset
angle_flag = False
angle = 90
dis = 0
see = False
# PWMServo.setServo(1, 1800, 500)
# PWMServo.setServo(2, 850, 500)
time.sleep(0.5)
# SSR.change_action_value("00", 1) # stand
while True:
if reset == 1: # 跳关或者重置
cv2.destroyAllWindows()
break
OrgFrame = org_img
frame = cv2.resize(OrgFrame, (resize_width, resize_height), interpolation=cv2.INTER_LINEAR)
# cv2.imshow('init', frame)
# 获取图像中心点坐标x, y
center = []
# 开始处理图像
hsv = cv2.cvtColor(frame, cv2.COLOR_BGR2HSV)
hsv = cv2.GaussianBlur(hsv, (3, 3), 3)
Imask = cv2.inRange(hsv, color_dict['black_dir']['Lower'], color_dict['black_dir']['Upper'])
Imask = cv2.erode(Imask, None, iterations=2)
Imask = cv2.dilate(Imask, np.ones((3, 3), np.uint8), iterations=2)
# cv2.imshow('black', Imask)
_, cnts, hierarchy = cv2.findContours(Imask, cv2.RETR_EXTERNAL, cv2.CHAIN_APPROX_TC89_L1) # 找出所有轮廓
cnt_sum = getLineSumContour(cnts, area=1)
cv2.drawContours(frame, cnt_sum, -1, (255, 0, 255), 3)
if cnt_sum is not None:
see = True
rect = cv2.minAreaRect(cnt_sum) # 最小外接矩形
box = np.int0(cv2.boxPoints(rect)) # 最小外接矩形的四个顶点
if math.sqrt(math.pow(box[3, 1] - box[0, 1], 2) + math.pow(box[3, 0] - box[0, 0], 2)) > math.sqrt(
math.pow(box[3, 1] - box[2, 1], 2) + math.pow(box[3, 0] - box[2, 0], 2)):
if box[3, 0] - box[0, 0] == 0:
angle = 90
else:
angle = - math.atan((box[3, 1] - box[0, 1]) / (box[3, 0] - box[0, 0])) * 180.0 / math.pi
if box[3, 1] + box[0, 1] > box[2, 1] + box[1, 1]:
edge_y1, edge_y2 = box[3, 1], box[0, 1]
dis = int((edge_y1 + edge_y2) / 2)
cv2.circle(OrgFrame, (int((box[3, 0] + box[0, 0]) / 2), int((box[3, 1] + box[0, 1]) / 2)), 10,
(0, 0, 255), -1) # 画出中心点
else:
edge_y1, edge_y2 = box[2, 1], box[1, 1]
dis = int((edge_y1 + edge_y2) / 2)
cv2.circle(OrgFrame, (int((box[2, 0] + box[1, 0]) / 2), int((box[2, 1] + box[1, 1]) / 2)), 10,
(0, 0, 255), -1) # 画出中心点
else:
if box[3, 0] - box[2, 0] == 0:
angle = 90
else:
angle = - math.atan(
(box[3, 1] - box[2, 1]) / (box[3, 0] - box[2, 0])) * 180.0 / math.pi # 负号是因为坐标原点的问题
if box[3, 1] + box[2, 1] > box[0, 1] + box[1, 1]:
edge_y1, edge_y2 = box[3, 1], box[2, 1]
dis = int((edge_y1 + edge_y2) / 2)
cv2.circle(OrgFrame, (int((box[3, 0] + box[2, 0]) / 2), int((box[3, 1] + box[2, 1]) / 2)), 10,
(0, 0, 255), -1) # 画出中心点
else:
edge_y1, edge_y2 = box[0, 1], box[1, 1]
dis = int((edge_y1 + edge_y2) / 2)
cv2.circle(OrgFrame, (int((box[0, 0] + box[1, 0]) / 2), int((box[0, 1] + box[1, 1]) / 2)), 10,
(0, 0, 255), -1) # 画出中心点
else:
see = False
cv2.putText(frame, "angle:" + str(angle),
(10, frame.shape[0] - 35), cv2.FONT_HERSHEY_SIMPLEX, 0.65, (0, 0, 255), 2)
# cv2.imshow('frame', frame)
# cv2.waitKey(1)
if not see: # not see the edge
cv2.destroyAllWindows()
break
else:
print(dis, angle)
if dis < 80:
if angle > -13:
# SSR.change_action_value("202", 1) # 左转小
print("left angle small")
elif angle < -16:
# SSR.change_action_value("203", 1) # 右转小
print("right angle small")
else:
break
elif dis > 400:
if angle > -24:
# SSR.change_action_value("202", 1) # 左转小
print("left angle small")
elif angle < -28:
# SSR.change_action_value("203", 1) # 右转小
print("right angle small")
else:
break
else:
if angle > -18:
# SSR.change_action_value("202", 1) # 左转小
print("left angle small")
elif angle < -22:
# SSR.change_action_value("203", 1) # 右转小
print("right angle small")
else:
break
time.sleep(0.2)
def judge_color():
global org_img
color = 'blue' # blue
border = cv2.copyMakeBorder(org_img, 12, 12, 16, 16, borderType=cv2.BORDER_CONSTANT,
value=(255, 255, 255)) # 扩展白边,防止边界无法识别
org_img_copy = cv2.resize(org_img, (r_w, r_h), interpolation=cv2.INTER_CUBIC) # 将图片缩放
frame_gauss = cv2.GaussianBlur(org_img_copy, (3, 3), 0) # 高斯模糊
frame_hsv = cv2.cvtColor(frame_gauss, cv2.COLOR_BGR2Lab) # 将图片转换到HSV空间
# frame_temp_1=cv2.inRange(frame_hsv, lab_range['blue'][0], lab_range['blue'][1]) # 对原图像和掩模(颜色的字典)进行位运算
frame_green = cv2.inRange(frame_hsv, lab_range['green'][0],
lab_range['green'][1]) # 对原图像和掩模(颜色的字典)进行位运算
opened_green = cv2.morphologyEx(frame_green, cv2.MORPH_OPEN, np.ones((3, 3), np.uint8)) # 开运算 去噪点
closed_green = cv2.morphologyEx(opened_green, cv2.MORPH_CLOSE, np.ones((3, 3), np.uint8)) # 闭运算 封闭连接
rgb_image = cv2.cvtColor(org_img_copy, cv2.COLOR_BGR2RGB)
result_green = cv2.bitwise_and(rgb_image, rgb_image, mask=closed_green)
frame_blue = cv2.inRange(frame_hsv, lab_range['blue'][0], lab_range['blue'][1]) # 对原图像和掩模(颜色的字典)进行位运算
opened_blue = cv2.morphologyEx(frame_blue, cv2.MORPH_OPEN, np.ones((3, 3), np.uint8)) # 开运算 去噪点
closed_blue = cv2.morphologyEx(opened_blue, cv2.MORPH_CLOSE, np.ones((3, 3), np.uint8)) # 闭运算 封闭连接
# rgb_image = cv2.cvtColor(org_img_copy, cv2.COLOR_BGR2RGB)
result_blue = cv2.bitwise_and(rgb_image, rgb_image, mask=closed_blue)
(image, contours_blue, hierarchy) = cv2.findContours(closed_blue, cv2.RETR_LIST, cv2.CHAIN_APPROX_NONE)
(image, contours_green, hierarchy) = cv2.findContours(closed_green, cv2.RETR_LIST, cv2.CHAIN_APPROX_NONE)
areaMaxContour, area_max_blue = getAreaMaxContour(contours_blue)
areaMaxContour, area_max_green = getAreaMaxContour(contours_green)
if area_max_blue > area_max_green:
color = 'blue'
else:
color = 'green'
return color
def check_stick():
global org_img
org_img_copy = cv2.resize(org_img.copy()[:,0:580], (r_w, r_h), interpolation=cv2.INTER_CUBIC) # 将图片缩放
frame_gauss = cv2.GaussianBlur(org_img_copy, (3, 3), 0) # 高斯模糊
frame_hsv = cv2.cvtColor(frame_gauss, cv2.COLOR_BGR2Lab) # 将图片转换到HSV空间
frame_door = cv2.inRange(frame_hsv[20:120, 0:640], lab_range['blue'][0],
lab_range['blue'][1]) # 对原图像和掩模(颜色的字典)进行位运算
opened_door = cv2.morphologyEx(frame_door, cv2.MORPH_OPEN, np.ones(( ), np.uint8)) # 开运算 去噪点
closed_door = cv2.morphologyEx(opened_door, cv2.MORPH_CLOSE, np.ones((3, 3), np.uint8)) # 闭运算 封闭连接
(image_door, contours_door, hierarchy_door) = cv2.findContours(closed_door, cv2.RETR_LIST,
cv2.CHAIN_APPROX_NONE) # 找出轮廓cv2.CHAIN_APPROX_NONE
cv2.imshow('check', closed_door)
areaMaxContour_door_1, area_max_door = getAreaMaxContour(contours_door, 1000)
if areaMaxContour_door_1 is None:
print('stick done with no stick')
SSR.change_action_value("go_middle_change_3", 5) # gogogo
time.sleep(10)
return
left_count = 0
SSR.serial_setServo(19, 600, 500)
time.sleep(3)
org_img_copy = cv2.resize(org_img.copy()[:,0:580], (r_w, r_h), interpolation=cv2.INTER_CUBIC) # 将图片缩放
frame_gauss = cv2.GaussianBlur(org_img_copy, (3, 3), 0) # 高斯模糊
frame_hsv = cv2.cvtColor(frame_gauss, cv2.COLOR_BGR2Lab) # 将图片转换到HSV空间
frame_door = cv2.inRange(frame_hsv[20:120, 0:640], lab_range['blue'][0],
lab_range['blue'][1]) # 对原图像和掩模(颜色的字典)进行位运算
opened_door = cv2.morphologyEx(frame_door, cv2.MORPH_OPEN, np.ones(( ), np.uint8)) # 开运算 去噪点
closed_door = cv2.morphologyEx(opened_door, cv2.MORPH_CLOSE, np.ones((3, 3), np.uint8)) # 闭运算 封闭连接
(image_door, contours_door, hierarchy_door) = cv2.findContours(closed_door, cv2.RETR_LIST,
cv2.CHAIN_APPROX_NONE) # 找出轮廓cv2.CHAIN_APPROX_NONE
cv2.imshow('check', closed_door)
SSR.serial_setServo(19, 500, 500)
time.sleep(1)
if contours_door is not None:
areaMaxContour_door_1, area_max_door = getAreaMaxContour(contours_door, 500)
if areaMaxContour_door_1 is not None:
if len(contours_door) > 1:
areaMaxContour_door_2, area_max_door = getAreaMaxContour(contours_door, 500)
if areaMaxContour_door_2 is not None:
print('get to left')
SSR.change_action_value("left_move_new_8", 1)
time.sleep(1)
left_count = 1
return
if left_count == 0:
SSR.serial_setServo(19, 400, 500)
time.sleep(3)
org_img_copy = cv2.resize(org_img.copy()[:,0:580], (r_w, r_h), interpolation=cv2.INTER_CUBIC) # 将图片缩放
frame_gauss = cv2.GaussianBlur(org_img_copy, (3, 3), 0) # 高斯模糊
frame_hsv = cv2.cvtColor(frame_gauss, cv2.COLOR_BGR2Lab) # 将图片转换到HSV空间
frame_door = cv2.inRange(frame_hsv[20:120, 0:640], lab_range['blue'][0],
lab_range['blue'][1]) # 对原图像和掩模(颜色的字典)进行位运算
opened_door = cv2.morphologyEx(frame_door, cv2.MORPH_OPEN, np.ones(( ), np.uint8)) # 开运算 去噪点
closed_door = cv2.morphologyEx(opened_door, cv2.MORPH_CLOSE, np.ones((3, 3), np.uint8)) # 闭运算 封闭连接
(image_door, contours_door, hierarchy_door) = cv2.findContours(closed_door, cv2.RETR_LIST,
cv2.CHAIN_APPROX_NONE) # 找出轮廓cv2.CHAIN_APPROX_NONE
SSR.serial_setServo(19, 500, 500)
time.sleep(1)
if contours_door is not None:
areaMaxContour_door_1, area_max_door = getAreaMaxContour(contours_door, 300)
if areaMaxContour_door_1 is not None:
if len(contours_door) > 1:
areaMaxContour_door_2, area_max_door = getAreaMaxContour(contours_door, 300)
if areaMaxContour_door_2 is not None:
print('get to right')
SSR.change_action_value("right_move_new_4", 1)
time.sleep(0.8)
left_count = 1
return
print('stick done ')
SSR.change_action_value("go_middle_change_3", 10) # gogogo
time.sleep(10)
########################## 关卡 ##########################
# 第1关:起点
def start_door(width, height):
global org_img, debug, isstop
# SSR.serial_setServo(20, 450, 500)
SSR.serial_setServo(20, 450, 500)
time.sleep(1)
door_count = 0
no_door_count = 0
print('进入start_door')
while True:
t1 = cv2.getTickCount()
border = cv2.copyMakeBorder(org_img, 12, 12, 16, 16, borderType=cv2.BORDER_CONSTANT,
value=(255, 255, 255)) # 扩展白边,防止边界无法识别
org_img_copy = cv2.resize(border, (width, height), interpolation=cv2.INTER_CUBIC) # 将图片缩放
frame_gauss = cv2.GaussianBlur(org_img_copy, (3, 3), 0) # 高斯模糊
frame_hsv = cv2.cvtColor(frame_gauss, cv2.COLOR_BGR2HSV) # 将图片转换到HSV空间
frame_door1 = cv2.inRange(frame_hsv, color_dict['yellow_door']['Lower'],
color_dict['yellow_door']['Upper']) # 对原图像和掩模(颜色的字典)进行位运算
frame_door2 = cv2.inRange(frame_hsv, color_dict['black']['Lower'],
color_dict['black']['Upper']) # 对原图像和掩模(颜色的字典)进行位运算
frame_door = cv2.add(frame_door1, frame_door2)
opened = cv2.morphologyEx(frame_door, cv2.MORPH_OPEN, np.ones((3, 3), np.uint8)) # 开运算 去噪点
closed = cv2.morphologyEx(opened, cv2.MORPH_CLOSE, np.ones((3, 3), np.uint8)) # 闭运算 封闭连接
# (image, contours, hierarchy) = cv2.findContours(closed, cv2.RETR_EXTERNAL, cv2.CHAIN_APPROX_NONE) # 找出轮廓
_, contours, hierarchy = cv2.findContours(closed, cv2.RETR_EXTERNAL, cv2.CHAIN_APPROX_NONE) # 找出轮廓
areaMaxContour, area_max = getAreaMaxContour(contours, 25) # 找出最大轮廓
percent = round(100 * area_max / (width * height), 2) # 最大轮廓的百分比
if areaMaxContour is not None:
rect = cv2.minAreaRect(areaMaxContour) # 矩形框选
box = np.int32(cv2.boxPoints(rect)) # 点的坐标
if debug:
cv2.drawContours(org_img_copy, [box], 0, (153, 200, 0), 2) # 将最小外接矩形画在图上
if debug:
# cv2.imshow('orginal frame', org_img)
# cv2.imshow('closed', closed) # 显示图像
cv2.putText(org_img_copy, 'area: ' + str(percent) + '%', (10, 100), cv2.FONT_HERSHEY_SIMPLEX, 0.7, (0, 0, 255), 2)
t2 = cv2.getTickCount()
time_r = (t2 - t1) / cv2.getTickFrequency()
fps = 1.0 / time_r
# cv2.putText(org_img_copy, "fps:" + str(int(fps)), (30, 200), cv2.FONT_HERSHEY_SIMPLEX, 0.65, (0, 0, 255), 2)
# cv2.moveWindow('orgFrame', img_center_x, 100) # 显示框位置
# cv2.imshow('org_img_copy', org_img_copy) # 显示图像
# cv2.waitKey(3)
# 根据比例得到是否前进的信息
if percent > 20:
print(percent)
print('stop')
isstop = True
# SSR.change_action_value("1",10) # 静止
time.sleep(0.1)
door_count += 1
no_door_count = 0
elif door_count >= 10:
no_door_count += 1
if no_door_count >= 10:
isstop = False
print('gogogo')
print(percent)
SSR.change_action_value("go_middle_stair", 5) # gogogo
time.sleep(6)
break
else:
pass
print("door_count = ", door_count, " no_door_count = ", no_door_count)
# cv2.destroyAllWindows()
# time.sleep(0.5)
# 第2关:过坑
def cross_trap_all():
if end == 0:
SSR.change_action_value("left_move_new_6", 2) # 左移
print("left")
time.sleep(1.2)
SSR.serial_setServo(20, 340, 500)
time.sleep(0.5)
SSR.serial_setServo(19, 500, 500)
time.sleep(0.5)
go()
# pass
# go()
def cross_trap():
global org_img, step, reset, end
# initialize
straight = False
left = False
left2 = False
right = False
right2 = False
# border = cv2.copyMakeBorder(org_img, 12, 12, 16, 16, borderType=cv2.BORDER_CONSTANT,
# value=(255, 255, 255)) # 扩展白边,防止边界无法识别
org_img_copy = cv2.resize(org_img[:,0:580], (r_w, r_h), interpolation=cv2.INTER_CUBIC) # 将图片缩放
frame_gauss = cv2.GaussianBlur(org_img_copy, (3, 3), 0) # 高斯模糊
frame_hsv = cv2.cvtColor(frame_gauss, cv2.COLOR_BGR2Lab) # 将图片转换到HSV空间
color = judge_color()
print(color)
# frame_temp_1=cv2.inRange(frame_hsv, lab_range['blue'][0], lab_range['blue'][1]) # 对原图像和掩模(颜色的字典)进行位运算
frame_green = cv2.inRange(frame_hsv, lab_range[color][0], lab_range[color][1]) # 对原图像和掩模(颜色的字典)进行位运算
opened = cv2.morphologyEx(frame_green, cv2.MORPH_OPEN, np.ones((3, 3), np.uint8)) # 开运算 去噪点
closed = cv2.morphologyEx(opened, cv2.MORPH_CLOSE, np.ones((3, 3), np.uint8)) # 闭运算 封闭连接
rgb_image = cv2.cvtColor(org_img_copy, cv2.COLOR_BGR2RGB)
result = cv2.bitwise_and(rgb_image, rgb_image, mask=closed)
# print(closed)
cv2.imshow('closed', closed)
(image, contours, hierarchy) = cv2.findContours(closed, cv2.RETR_LIST,
cv2.CHAIN_APPROX_NONE) # 找出轮廓cv2.CHAIN_APPROX_NONE
image_filled = 255 * np.ones(closed.shape, np.uint8) # 用于识别色块的图像
areaMaxContour, area_max = getAreaMaxContour(contours)
image_line_detection = np.zeros(closed.shape, np.uint8)
image_line_detection = cv2.drawContours(image_line_detection, areaMaxContour, -1, 255, 2)
lines = cv2.HoughLinesP(image_line_detection, 1, np.pi / 180, 30, 300, 5)
################################调整转向部分##############################
tangent_list = []
length_list = []
image_copy = copy.copy(org_img)
if lines is not None:
for line in lines:
x1, y1, x2, y2 = line[0]
if y1 < 410 and x2 - x1 != 0:
tangent_abs = np.abs((y2 - y1) / (x2 - x1))
if tangent_abs < 0.5:
length_list.append(np.abs(line[0, 0] - line[0, 2]))
tangent_list.append([x1, y1, x2, y2])
if len(tangent_list) > 0:
[x1_f, y1_f, x2_f, y2_f] = tangent_list[np.where(length_list == np.max(length_list))[0][0]]
tangent_used = -(y2_f - y1_f) / (x2_f - x1_f) #####标准tangent
else:
tangent_used = 0
[x1_f, y1_f, x2_f, y2_f] = [0, 0, 0, 0]
print(tangent_used)
cv2.line(image_copy, (x1_f, y1_f), (x2_f, y2_f), (0, 255, 0), 1)
if 0.20 > tangent_used > 0.07:
print("should turn left little")
SSR.change_action_value("turn_left", 1)
time.sleep(0.7)
elif tangent_used > 0.20:
print("should turn left large")
SSR.change_action_value("turn_left", 1)
time.sleep(0.7)
elif -0.07 > tangent_used > -0.20:
print("should turn right little")
SSR.change_action_value("turn_right", 1)
time.sleep(0.7)
elif tangent_used < - 0.20:
print("should turn right large")
SSR.change_action_value("turn_right", 1)
time.sleep(0.7)
print(y1_f, y2_f, area_max)
# cv2.imshow("image_line1", image_copy)
if y1_f > 340 and y2_f > 340 and area_max < 45000:
print("get end")
time.sleep(1)
SSR.change_action_value("go_middle_change_3", 3) # 前进
time.sleep(2)
SSR.change_action_value("right_move_new_2", 5) # 右移
time.sleep(15)
SSR.change_action_value("turn_right", 1)
time.sleep(3)
SSR.change_action_value("go_middle_change_3", 3) # 前进
time.sleep(2)
end = 1
return
##########################开始避障检测
if areaMaxContour is not None:
cv2.fillPoly(image_filled, pts=[areaMaxContour], color=0)
if len(contours) > 1:
contours.remove(areaMaxContour)
areaMaxContour, area_max = getAreaMaxContour(contours, 4000)
# print(area_max)
if area_max > 4000:
# pass
# print(areaMaxContour)
cv2.fillPoly(image_filled, pts=[areaMaxContour], color=255)
else:
print('trap_end')
time.sleep(1)
SSR.change_action_value("go_middle_change_3", 3) # 前进
time.sleep(2)
SSR.change_action_value("right_move_new_2", 3) # 右移
time.sleep(8)
#SSR.change_action_value("turn_right", 1)
#time.sleep(3)
SSR.change_action_value("go_middle_change_3", 1) # 前进
time.sleep(2)
end = 1
return
image_line_detection = image_line_detection[15:465, 20:620]
image_line_detection = cv2.copyMakeBorder(image_line_detection, 15, 15, 20, 20, borderType=cv2.BORDER_CONSTANT,
value=0)
Imask = image_filled
n = -1
obscle_list = []
obscle_list_last = []
for r in roi:
n += 1
blobs = Imask[r[0]:r[1], r[2]:r[3]]
_, cnts, hierarchy = cv2.findContours(blobs, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)
cnt_large, _ = getAreaMaxContour(cnts, 200)
#####################################change 80 to 200##########################
if cnt_large is not None:
# print(area_max)
lefttop_x = r[2]
lefttop_y = r[0]
rightbottom_x = r[3]
rightbottom_y = r[1]
cv2.rectangle(image_copy, (lefttop_x, lefttop_y), (rightbottom_x, rightbottom_y), (0, 255, 255), 2)
# cv2.imshow("what",org_img)
obscle_list.append([n // 9, n % 9])
s_straight = [[5, 4], [4, 4], [5, 3], [5, 5]]
# s_straight = [[5, 4], [4, 4]]
s_left_edge = [[4, 0], [3, 0], [2, 0], [1, 0]]
s_right_edge = [[4, 8], [3, 8], [2, 8], [1, 8]]
s_left_1 = [[4, 1], [3, 1], [2, 1], [4, 2]]
s_left_2 = [[3, 2], [2, 2], [1, 3], [2, 3]]
s_right_1 = [[4, 7], [3, 7], [2, 7], [1, 5]]
s_right_2 = [[4, 6], [3, 6], [2, 6], [2, 5]]
s_left_middle_1 = [[4, 4], [4, 3], [5, 4], [5, 3]]
s_left_middle_2 = [[5, 2], [5, 3], [5, 4]]
s_right_middle_1 = [[4, 4], [4, 5], [5, 4], [5, 5]]
s_right_middle_2 = [[5, 4], [5, 5], [5, 6]]
if all(s not in obscle_list for s in s_straight):
straight = True
left = False
left2 = False
right = False
right2 = False
# elif all(s in obscle_list for s in s_edge_left) and any(s in obscle_list for s in s1_2):
elif all(s in obscle_list for s in s_right_middle_1) or all(s in obscle_list for s in s_right_middle_2):
straight = False
left = False
left2 = True
right = False
right2 = False
elif all(s in obscle_list for s in s_left_middle_1) or all(s in obscle_list for s in s_left_middle_2):
straight = False
left = False
left2 = False
right = False
right2 = True
# elif all(s in obscle_list for s in s_edge_right) and any(s in obscle_list for s in s1_3):
elif all(s not in obscle_list for s in s_right_1) or all(s not in obscle_list_last for s in s_right_2):
straight = False
left = True
left2 = False
right = False
right2 = False
elif all(s not in obscle_list for s in s_left_1) or all(s not in obscle_list_last for s in s_left_2):
straight = False
left = False
left2 = False
right = True
right2 = False
# elif all(s not in obscle_list for s in s4_1) and all(s not in obscle_list_last for s in s2_1) and any(
# s in obscle_list for s in s4_2):
# straight = False
# left = True
# left2 = False
# right = False
# right2 = False
# elif all(s not in obscle_list for s in s5_1) and all(s not in obscle_list_last for s in s3_1) and any(
# s in obscle_list for s in s5_2):
# straight = False
# left = False
# left2 = False
# right = True
# right2 = False
s1 = [[5, 4], [5, 3], [5, 2], [5, 1], [5, 5], [5, 6], [5, 7], [5, 0], [5, 8]]
# s1 = [[5, 2], [5, 1], [5, 6], [5, 7]]
s1_1 = [[5, 4], [5, 3], [5, 2], [5, 1], [5, 5], [5, 6], [5, 7]]
# s1_2 = [[5, 4], [5, 3], [5, 2], [5, 1], [5, 5], [5, 6], [5, 7], [5, 8]]
s1_3 = [[5, 4], [5, 3], [5, 2], [5, 1], [5, 5], [5, 6], [5, 7], [5, 0]]
s2_1 = [[5, 1], [5, 0], [5, 3], [5, 2]]
s2_2 = [[5, 4], [5, 5], [5, 6]]
s3_1 = [[5, 5], [5, 6], [5, 7], [5, 8]]
s3_2 = [[5, 4], [5, 3], [5, 2]]
s4_1 = [[5, 1], [5, 0], [5, 3], [5, 2], [5, 4], [5, 5], [5, 6]]
s4_2 = [[5, 7], [5, 8]]
s5_1 = [[5, 5], [5, 6], [5, 7], [5, 8], [5, 3], [5, 2], [5, 4]]
s5_2 = [[5, 1], [5, 0]]
s_edge_left = [[4, 0], [3, 0], [2, 0], [1, 0]]
s_edge_right = [[4, 8], [3, 8], [2, 8], [1, 8]]
s_adjust = [[4, 4], [4, 3], [4, 2], [4, 1], [4, 5], [4, 6], [4, 7], [4, 0], [4, 8]]
s_under = [[5, 4], [5, 3], [5, 2], [5, 1], [5, 5], [5, 6], [5, 7], [5, 0], [5, 8], [4, 4], [4, 3], [4, 2],
[4, 1], [4, 5], [4, 6], [4, 7], [4, 0], [3, 8], [3, 4], [3, 3], [3, 2], [3, 1], [3, 5], [3, 6],
[3, 7], [3, 0], [3, 8]]
cv2.putText(image_copy,
"straight:" + str(straight) + " left:" + str(left) + " right:" + str(right) + " left2:" + str(
left2) + " right2:" + str(right2),
(10, org_img.shape[0] - 35), cv2.FONT_HERSHEY_SIMPLEX, 0.65, (0, 0, 255), 2)
cv2.putText(image_copy, "step:" + str(step),
(10, org_img.shape[0] - 55), cv2.FONT_HERSHEY_SIMPLEX, 0.65, (0, 0, 255), 2)
# cv2.putText(OrgFrame,"finish:"+str(obscle_finish),(10,OrgFrame.shape[0]-75),cv2.FONT_HERSHEY_SIMPLEX,0.65,(0,0,255),2)
# cv2.imshow('frame', org_img)
# cv2.waitKey(3)
#########################正常避障部分 动作组换成move########################
isgo = False
count = 0
if step == 0:
if all(s not in obscle_list for s in s_under):
print("straight")
# SSR.change_action_value("239", 1) # 前进
count += 1
isgo = True
else:
if isgo:
pass
# SSR.change_action_value('157', 1)
isgo = False
step = 1
time.sleep(0.2)
elif step == 1:
if all(s not in obscle_list for s in s_under):
step = 0
elif (count >= 20) and any(s in obscle_list for s in s_adjust):
direction_only_angle(640, 480)
# PWMServo.setServo(1, 2090, 500)
# PWMServo.setServo(2, 1480, 500)
time.sleep(0.8)
count = 0
elif straight:
# SSR.change_action_value("go_forward", 1) # 前进
print("forward")
SSR.change_action_value("go_middle_change_3", 3) # 前进
time.sleep(1.5)
count += 1
elif left:
SSR.change_action_value("left_move_new_6", 1) # 左移
print("left")
time.sleep(1)
elif right:
SSR.change_action_value("right_move_new_2", 1) # 右移
print("right")
time.sleep(1)
elif left2 is True:
SSR.change_action_value("left_move_new_6", 1) # 左移
print("left*2")
time.sleep(1)
elif right2 is True:
SSR.change_action_value("right_move_new_2", 1) # 右移
print("right*2")
time.sleep(1)
else:
# SSR.change_action_value("1", 1) # 静止
print("stand_stand")
SSR.change_action_value("1", 1) # 右移
cv2.imshow("image_org", image_copy)
# cv2.imshow("image_filled", image_filled)
# cv2.waitKey(0)
cv2.imshow("image_line", image_line_detection)
# cv2.imshow("image1", result)
cv2.waitKey(3)
def go():
while True:
time1 = time.time()
cross_trap()
time2 = time.time()
print("spend", time2 - time1)
if end:
cv2.destroyAllWindows()
return
# lowThreshold = 0
# max_lowThreshold = 100
# ratio = 3
# kernel_size = 3
# gray = cv2.cvtColor(img, cv2.COLOR_BGR2GRAY)
# cv2.namedWindow('canny demo')
# cv2.createTrackbar('Min threshold', 'canny demo', lowThreshold, max_lowThreshold, CannyThreshold)
# CannyThreshold(0) # initialization
# if cv2.waitKey(0) == 27:
# cv2.destroyAllWindows()
# 第3关:地雷
roi = [(0, 80, 0, 70), (0, 80, 70, 140), (0, 80, 140, 210), (0, 80, 210, 240), (0, 80, 240, 400), (0, 80, 400, 430),
(0, 80, 430, 500),
(0, 80, 500, 570), (0, 80, 570, 640), (80, 160, 0, 70), (80, 160, 70, 140), (80, 160, 140, 210),
(80, 160, 210, 240),
(80, 160, 240, 400), (80, 160, 400, 430), (80, 160, 430, 500), (80, 160, 500, 570), (80, 160, 570, 640),
(160, 240, 0, 70),
(160, 240, 70, 140), (160, 240, 140, 210), (160, 240, 210, 240), (160, 240, 240, 400), (160, 240, 400, 430),
(160, 240, 430, 500),
(160, 240, 500, 570), (160, 240, 570, 640), (240, 320, 0, 70), (240, 320, 70, 140), (240, 320, 140, 210),
(240, 320, 210, 240),
(240, 350, 240, 400), (240, 320, 400, 430), (240, 320, 430, 500), (240, 320, 500, 570), (240, 320, 570, 640),
(320, 400, 0, 70), (320, 400, 70, 140), (320, 400, 140, 210), (320, 400, 210, 240), (350, 400, 240, 400),
(320, 400, 400, 430),
(320, 400, 430, 500), (320, 400, 500, 570), (320, 400, 570, 640), (400, 430, 0, 70), (400, 430, 70, 140),
(400, 430, 140, 210),
(400, 430, 210, 240), (400, 430, 240, 400), (400, 430, 400, 430), (400, 430, 430, 500), (400, 430, 500, 570),
(400, 430, 570, 640)]
# print(len(roi))
roi_mine = [(0, 80, 0, 70), (0, 80, 70, 140), (0, 80, 140, 210), (0, 80, 210, 280), (0, 80, 280, 360),
(0, 80, 360, 430),
(0, 80, 430, 500),
(0, 80, 500, 570), (0, 80, 570, 640), (80, 160, 0, 70), (80, 160, 70, 140), (80, 160, 140, 210),
(80, 160, 210, 280),
(80, 160, 280, 360), (80, 160, 360, 430), (80, 160, 430, 500), (80, 160, 500, 570), (80, 160, 570, 640),
(160, 240, 0, 70),
(160, 240, 70, 140), (160, 240, 140, 210), (160, 240, 210, 280), (160, 240, 280, 360), (160, 240, 360, 430),
(160, 240, 430, 500),
(160, 240, 500, 570), (160, 240, 570, 640), (240, 320, 0, 70), (240, 320, 70, 140), (240, 320, 140, 210),
(240, 320, 210, 280),
(240, 320, 280, 360), (240, 320, 360, 430), (240, 320, 430, 500), (240, 320, 500, 570),
(240, 320, 570, 640),
(320, 400, 0, 70), (320, 400, 70, 140), (320, 400, 140, 210), (320, 400, 210, 280), (320, 400, 280, 360),
(320, 400, 360, 430),
(320, 400, 430, 500), (320, 400, 500, 570), (320, 400, 570, 640), (400, 480, 0, 70), (400, 480, 70, 140),
(400, 480, 140, 210),
(400, 480, 210, 280), (400, 480, 280, 360), (400, 480, 360, 430), (400, 480, 430, 500),
(400, 480, 500, 570),
(400, 480, 570, 640)]
def get_angle(color):
global org_img, blue_persent
org_img_copy = copy.copy(org_img)
org_img_copy = cv2.resize(org_img_copy, (r_w, r_h), interpolation=cv2.INTER_CUBIC) # 将图片缩放
frame_gauss = cv2.GaussianBlur(org_img_copy, (3, 3), 0) # 高斯模糊
frame_hsv = cv2.cvtColor(frame_gauss, cv2.COLOR_BGR2Lab) # 将图片转换到HSV空间
frame_green = cv2.inRange(frame_hsv, lab_range[color][0], lab_range[color][1]) # 对原图像和掩模(颜色的字典)进行位运算
opened = cv2.morphologyEx(frame_green, cv2.MORPH_OPEN, np.ones((5, 5), np.uint8)) # 开运算 去噪点
closed = cv2.morphologyEx(opened, cv2.MORPH_CLOSE, np.ones((3, 3), np.uint8)) # 闭运算 封闭连接
rgb_image = cv2.cvtColor(org_img_copy, cv2.COLOR_BGR2RGB)
#result = cv2.bitwise_and(rgb_image, rgb_image, mask=closed)
#cv2.imshow('closed', closed)
(image, contours, hierarchy) = cv2.findContours(closed, cv2.RETR_LIST,
cv2.CHAIN_APPROX_NONE) # 找出轮廓cv2.CHAIN_APPROX_NONE
# image_filled = 255 * np.ones(closed.shape, np.uint8) # 用于识别色块的图像
areaMaxContour, area_max = getAreaMaxContour(contours, 25)
center = (1, 1)
if areaMaxContour is not None:
rect = cv2.minAreaRect(areaMaxContour)
center, w_h, angle = rect # 中心点 宽高 旋转角度
# box = np.int0(cv2.boxPoints(rect)) # 点的坐标
image_line_detection = np.zeros(closed.shape, np.uint8)
image_line_detection = cv2.drawContours(image_line_detection, areaMaxContour, -1, 255, 2)
lines = cv2.HoughLinesP(image_line_detection, 1, np.pi / 180, 30, 300, 5)
tangent_list = []
length_list = []
image_copy = copy.copy(org_img)
if lines is not None:
for line in lines:
x1, y1, x2, y2 = line[0]
if y1 < 410 and x2 - x1 != 0:
tangent_abs = np.abs((y2 - y1) / (x2 - x1))
if tangent_abs < 0.5:
length_list.append(np.abs(line[0, 0] - line[0, 2]))
tangent_list.append([x1, y1, x2, y2])
if len(tangent_list) > 0:
[x1_f, y1_f, x2_f, y2_f] = tangent_list[np.where(length_list == np.max(length_list))[0][0]]
tangent_used = -(y2_f - y1_f) / (x2_f - x1_f) #####标准tangent
else:
tangent_used = 0
[x1_f, y1_f, x2_f, y2_f] = [0, 0, 0, 0]
print('angle is: ', tangent_used)
blue_persent = round(area_max * 100 / (r_w * r_h), 2)
print('percent', blue_persent)
# cv2.line(image_copy, (x1_f, y1_f), (x2_f, y2_f), (0, 255, 0), 3)
# cv2.circle(image_copy, (int(center[0]), int(center[1])), 5, (255, 0, 0), 2)
# cv2.imshow("image_line", image_copy)
return tangent_used
def obscle():
global org_img, step, reset, move_count, forward_count, blue_persent
right_count = 0
left_count = 0
straight = False # 直行信号
left = False # 左移信号
left2 = False # 遇到右边缘且前方有障碍
right = False # 右移
right2 = False # 遇到左边缘且前方有障碍
SSR.change_action_value("turn_left", 1)
time.sleep(0.8)
if org_img is None:
print('No image')
time.sleep(5)
# frame = cv2.resize(OrgFrame, (r_w, r_h), interpolation=cv2.INTER_LINEAR)
while True:
# OrgFrame = copy.copy(org_img)
# cv2.imshow('init', OrgFrame)
# cv2.waitKey(3)3
tangent_used = get_angle('blue')
head_degree = 410 - forward_count * 3
if head_degree < 380:
head_degree = 380
if move_count % 6 == 0: # abled
judge = True
while judge:
print("head up")
time.sleep(0.5)
SSR.serial_setServo(20, head_degree, 1000)
time.sleep(1)
tangent_used = get_angle('blue')
# OrgFrame = org_img
# #print(org_img)
# #cv2.imshow('init', OrgFrame)
# hsv = cv2.cvtColor(OrgFrame, cv2.COLOR_BGR2HSV)
# hsv = cv2.GaussianBlur(hsv, (3, 3), 0)
# Imask = cv2.inRange(hsv, color_dict['black_obstacle']['Lower'], color_dict['black_obstacle']['Upper'])
# # Imask = cv2.erode(Imask, None, iterations=2)
# Imask = cv2.dilate(Imask, np.ones((3, 3), np.uint8), iterations=2)
# cv2.imshow('black', Imask)
#
# Imask2 = cv2.inRange(hsv, color_dict['blue']['Lower'], color_dict['blue']['Upper'])
# Imask2 = cv2.erode(Imask2, None, iterations=2)
# Imask2 = cv2.dilate(Imask2, np.ones((3, 3), np.uint8), iterations=2)
# _, cnts2, hierarchy2 = cv2.findContours(Imask2, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)
# cv2.imshow('blue', Imask2)