From f3b719c46a5294f4590a32de1423f291fb985cba Mon Sep 17 00:00:00 2001 From: minibot-1 <paddy-hofmann@web.de> Date: Wed, 15 Mar 2023 15:02:49 +0000 Subject: [PATCH] minor changes to segment_sign --- minibot_vision/config/sign_detector.yaml | 14 +++----------- minibot_vision/config/sign_detector_default.yaml | 4 ++-- minibot_vision/scripts/SegmentSign.py | 3 ++- minibot_vision/scripts/ShapeDetector.py | 4 ++-- .../launch/traffic_sign_workshop.launch | 7 ------- 5 files changed, 9 insertions(+), 23 deletions(-) diff --git a/minibot_vision/config/sign_detector.yaml b/minibot_vision/config/sign_detector.yaml index e25bf9b..b90f8a8 100644 --- a/minibot_vision/config/sign_detector.yaml +++ b/minibot_vision/config/sign_detector.yaml @@ -1,11 +1,3 @@ -sign_detector: - canny_param1: 144 - canny_param2: 59 - img_height: 480 - img_width: 640 - max_depth: 1.0 - max_radius: 128 - min_depth: 0.2 - min_radius: 15 - visualize: false - zoom_threshold: 1.15 +sign_detector: {canny_param1: 47, canny_param2: 46, img_height: 1080, img_width: 1920, + max_depth: 1.0, max_radius: 128, min_depth: 0.2, min_radius: 15, visualize: false, + zoom_threshold: 1.15} diff --git a/minibot_vision/config/sign_detector_default.yaml b/minibot_vision/config/sign_detector_default.yaml index 1cd549c..f9188fc 100644 --- a/minibot_vision/config/sign_detector_default.yaml +++ b/minibot_vision/config/sign_detector_default.yaml @@ -1,7 +1,7 @@ # default params that got not overriden sign_detector: - img_height: 480 - img_width: 640 + img_height: 1080 + img_width: 1920 canny_param1: 100 canny_param2: 100 # good light: 40; bad light: 100 min_depth: 0.2 diff --git a/minibot_vision/scripts/SegmentSign.py b/minibot_vision/scripts/SegmentSign.py index c0991da..64f7a64 100644 --- a/minibot_vision/scripts/SegmentSign.py +++ b/minibot_vision/scripts/SegmentSign.py @@ -14,6 +14,7 @@ from minibot_msgs.srv import segment_sign_command, segment_sign_commandRequest, # *** hyper params *** #IMG_RES = (480, 640) IMG_RES = (rospy.get_param("sign_detector/img_height", 1080), rospy.get_param("sign_detector/img_width", 1920)) #(1080,1920) +DEPTH_RES = (480, 640) TENSOR_RES = (224, 224) # gazebo 70,30; rviz 70, 20; real 100 40 canny = rospy.get_param("sign_detector/canny_param1", 100) #100 @@ -68,7 +69,7 @@ def circular_mean(p, r, arr : np.array): sum_px_values = 0 count_px = 0 for x, y in xy: - if x >= IMG_RES[1] or y >= IMG_RES[0]: + if x >= DEPTH_RES[1] or y >= DEPTH_RES[0]: continue if (x - p[0])**2 + (y - p[1])**2 < r**2: sum_px_values += arr[y, x] diff --git a/minibot_vision/scripts/ShapeDetector.py b/minibot_vision/scripts/ShapeDetector.py index 5653289..c2c3df9 100644 --- a/minibot_vision/scripts/ShapeDetector.py +++ b/minibot_vision/scripts/ShapeDetector.py @@ -93,7 +93,7 @@ def do_shape_detection(img_rgb, img_depth): if VISUALIZE: cv2.imshow('thresh img', thresh1) - contours, hierarchy = cv2.findContours(thresh1, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE) + contours, hierarchy = cv2.findContours(thresh1, cv2.RETR_TREE, cv2.CHAIN_APPROX_SIMPLE)[-2:] keypoints = [] for cnt in contours: approx = cv2.approxPolyDP(cnt,0.01*cv2.arcLength(cnt,True),True) @@ -142,4 +142,4 @@ if __name__=="__main__": #cv2.imshow("Shape", img_processed) - rate.sleep() \ No newline at end of file + rate.sleep() diff --git a/minibot_workshops/launch/traffic_sign_workshop.launch b/minibot_workshops/launch/traffic_sign_workshop.launch index 0d32100..4f26916 100644 --- a/minibot_workshops/launch/traffic_sign_workshop.launch +++ b/minibot_workshops/launch/traffic_sign_workshop.launch @@ -1,12 +1,5 @@ <?xml version="1.0"?> <launch> - <include file="$(find rosbridge_server)/launch/rosbridge_websocket.launch" > - <arg name="port" value="9090"/> - </include> - <include file="$(find minibot)/launch/bringup_minibot.launch" > - <arg name="run_arm" value="false" /> - </include> - <include file="$(find minibot_vision)/launch/capture_imgs.launch" > <arg name="remote_node" value="true" /> </include> -- GitLab