From 77099281c94595fa4b94fc14e46c93609cb63252 Mon Sep 17 00:00:00 2001 From: hellososhi <22724971+hellososhi@users.noreply.github.com> Date: Sun, 23 Jul 2023 16:20:32 +0900 Subject: [PATCH 1/8] modify Dockerfile --- docker/Dockerfile | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/docker/Dockerfile b/docker/Dockerfile index 2954e43..158608c 100644 --- a/docker/Dockerfile +++ b/docker/Dockerfile @@ -78,8 +78,8 @@ RUN mkdir -p external_catkin_ws/src && \ # install PyTorch RUN pip install torch==1.10.1+cu111 torchvision==0.11.2+cu111 torchaudio==0.10.1 -f https://download.pytorch.org/whl/torch_stable.html -# install YOLOv3 -RUN pip install pytorchyolo +# install YOLOv8 +RUN pip install ultralytics WORKDIR /root/ From 99def19b68213d62732640ea15ea29fb9749894a Mon Sep 17 00:00:00 2001 From: hellososhi <22724971+hellososhi@users.noreply.github.com> Date: Sun, 23 Jul 2023 16:52:31 +0900 Subject: [PATCH 2/8] modify objectt_detection.py --- .../scripts/object_detection.py | 47 ++++++++----------- 1 file changed, 20 insertions(+), 27 deletions(-) diff --git a/catkin_ws/src/three-dimensions_tutorial/scripts/object_detection.py b/catkin_ws/src/three-dimensions_tutorial/scripts/object_detection.py index e4b1069..05b5545 100755 --- a/catkin_ws/src/three-dimensions_tutorial/scripts/object_detection.py +++ b/catkin_ws/src/three-dimensions_tutorial/scripts/object_detection.py @@ -1,13 +1,15 @@ #!/usr/bin/env python3 +import copy +from typing import List + +import cv2 import rospy -from sensor_msgs.msg import Image from cv_bridge import CvBridge -from pytorchyolo import detect, models -import matplotlib.pyplot as plt -import matplotlib.patches as patches -import cv2 -import copy +from sensor_msgs.msg import Image +from ultralytics import YOLO +from ultralytics.engine.results import Results + class ObjectDetection: def __init__(self): @@ -17,44 +19,35 @@ def __init__(self): self.detection_result_pub = rospy.Publisher('/detection_result', Image, queue_size=10) # Subscriber - rgb_sub = rospy.Subscriber('/camera/color/image_raw', Image, self.callback_rgb) + rospy.Subscriber('/camera/color/image_raw', Image, self.callback_rgb) self.bridge = CvBridge() self.rgb_image = None + self.model = YOLO('yolov8n.pt') + def callback_rgb(self, data): cv_array = self.bridge.imgmsg_to_cv2(data, 'bgr8') - cv_array = cv2.cvtColor(cv_array, cv2.COLOR_BGR2RGB) self.rgb_image = cv_array def process(self): - path = "/root/roomba_hack/catkin_ws/src/three-dimensions_tutorial/yolov3/" - - # load category - with open(path+"data/coco.names") as f: - category = f.read().splitlines() - - # prepare model - model = models.load_model(path+"config/yolov3.cfg", path+"weights/yolov3.weights") - while not rospy.is_shutdown(): if self.rgb_image is None: continue - # inference - tmp_image = copy.copy(self.rgb_image) - boxes = detect.detect_image(model, tmp_image) - # [[x1, y1, x2, y2, confidence, class]] + results: List[Results] = self.model.predict(self.rgb_image) - # plot bouding box - for box in boxes: - x1, y1, x2, y2 = map(int, box[:4]) - cls_pred = int(box[5]) + # plot bounding box + tmp_image = copy.deepcopy(self.rgb_image) + for result in results: + boxes = result.boxes.cpu().numpy() + names = result.names + x1, y1, x2, y2 = map(int, boxes.xyxy[0][:4]) + cls_pred = boxes.cls[0] tmp_image = cv2.rectangle(tmp_image, (x1, y1), (x2, y2), (0, 255, 0), 3) - tmp_image = cv2.putText(tmp_image, category[cls_pred], (x1, y1), cv2.FONT_HERSHEY_SIMPLEX, 1.0, (0, 255, 0), 2) + tmp_image = cv2.putText(tmp_image, names[cls_pred], (x1, y1), cv2.FONT_HERSHEY_SIMPLEX, 1.0, (0, 255, 0), 2) # publish image - tmp_image = cv2.cvtColor(tmp_image, cv2.COLOR_RGB2BGR) detection_result = self.bridge.cv2_to_imgmsg(tmp_image, "bgr8") self.detection_result_pub.publish(detection_result) From 04459c524c58daf6d6b68ea1cf5e5d6d31beb8d7 Mon Sep 17 00:00:00 2001 From: hellososhi <22724971+hellososhi@users.noreply.github.com> Date: Fri, 4 Aug 2023 19:12:02 +0900 Subject: [PATCH 3/8] object_detection.py --- .../scripts/object_detection.py | 11 +++++++---- 1 file changed, 7 insertions(+), 4 deletions(-) diff --git a/catkin_ws/src/three-dimensions_tutorial/scripts/object_detection.py b/catkin_ws/src/three-dimensions_tutorial/scripts/object_detection.py index 05b5545..b342fdd 100755 --- a/catkin_ws/src/three-dimensions_tutorial/scripts/object_detection.py +++ b/catkin_ws/src/three-dimensions_tutorial/scripts/object_detection.py @@ -42,10 +42,13 @@ def process(self): for result in results: boxes = result.boxes.cpu().numpy() names = result.names - x1, y1, x2, y2 = map(int, boxes.xyxy[0][:4]) - cls_pred = boxes.cls[0] - tmp_image = cv2.rectangle(tmp_image, (x1, y1), (x2, y2), (0, 255, 0), 3) - tmp_image = cv2.putText(tmp_image, names[cls_pred], (x1, y1), cv2.FONT_HERSHEY_SIMPLEX, 1.0, (0, 255, 0), 2) + for xyxy, conf, cls in zip(boxes.xyxy, boxes.conf, boxes.cls): + if conf < 0.5: + continue + x1, y1, x2, y2 = map(int, xyxy[:4]) + cls_pred = cls + tmp_image = cv2.rectangle(tmp_image, (x1, y1), (x2, y2), (0, 255, 0), 3) + tmp_image = cv2.putText(tmp_image, names[cls_pred], (x1, y1), cv2.FONT_HERSHEY_SIMPLEX, 1.0, (0, 255, 0), 2) # publish image detection_result = self.bridge.cv2_to_imgmsg(tmp_image, "bgr8") From 10b2ca3d29f5af7566d79ee29c364025c3aeb3f2 Mon Sep 17 00:00:00 2001 From: hellososhi <22724971+hellososhi@users.noreply.github.com> Date: Fri, 4 Aug 2023 19:27:45 +0900 Subject: [PATCH 4/8] detection_mask.py --- .../scripts/detection_mask.py | 59 +++++++++---------- 1 file changed, 28 insertions(+), 31 deletions(-) diff --git a/catkin_ws/src/three-dimensions_tutorial/scripts/detection_mask.py b/catkin_ws/src/three-dimensions_tutorial/scripts/detection_mask.py index 782c208..76c7f36 100755 --- a/catkin_ws/src/three-dimensions_tutorial/scripts/detection_mask.py +++ b/catkin_ws/src/three-dimensions_tutorial/scripts/detection_mask.py @@ -1,15 +1,16 @@ #!/usr/bin/env python3 +import copy +from typing import List -import rospy +import cv2 import message_filters -from sensor_msgs.msg import Image, CameraInfo -from cv_bridge import CvBridge -from pytorchyolo import detect, models -import matplotlib.pyplot as plt -import matplotlib.patches as patches import numpy as np -import cv2 -import copy +import rospy +from cv_bridge import CvBridge +from sensor_msgs.msg import CameraInfo, Image +from ultralytics import YOLO +from ultralytics.engine.results import Results + class DetectionMask: def __init__(self): @@ -29,6 +30,8 @@ def __init__(self): self.bridge = CvBridge() self.rgb_image, self.depth_image, self.camera_info = None, None, None + self.model = YOLO('yolov8n.pt') + def callback_rgbd(self, data1, data2, data3): cv_array = self.bridge.imgmsg_to_cv2(data1, 'bgr8') cv_array = cv2.cvtColor(cv_array, cv2.COLOR_BGR2RGB) @@ -40,39 +43,33 @@ def callback_rgbd(self, data1, data2, data3): self.camera_info = data3 def process(self): - path = "/root/roomba_hack/catkin_ws/src/three-dimensions_tutorial/yolov3/" - - # load category - with open(path+"data/coco.names") as f: - category = f.read().splitlines() - - # prepare model - model = models.load_model(path+"config/yolov3.cfg", path+"weights/yolov3.weights") - while not rospy.is_shutdown(): if self.rgb_image is None: continue - # inference tmp_rgb_image = copy.copy(self.rgb_image) tmp_depth_image = copy.copy(self.depth_image) tmp_camera_info = copy.copy(self.camera_info) - boxes = detect.detect_image(model, tmp_rgb_image) - # [[x1, y1, x2, y2, confidence, class]] - depth_mask = np.zeros_like(tmp_depth_image) - # plot bouding box - for box in boxes: - x1, y1, x2, y2 = map(int, box[:4]) - cls_pred = int(box[5]) - tmp_rgb_image = cv2.rectangle(tmp_rgb_image, (x1, y1), (x2, y2), (0, 255, 0), 3) - tmp_rgb_image = cv2.putText(tmp_rgb_image, category[cls_pred], (x1, y1), cv2.FONT_HERSHEY_SIMPLEX, 1.0, (0, 255, 0), 2) + results: List[Results] = self.model.predict(self.rgb_image) + + # plot bounding box + tmp_image = copy.deepcopy(self.rgb_image) + for result in results: + boxes = result.boxes.cpu().numpy() + names = result.names + if len(boxes.xyxy) == 0: + continue + x1, y1, x2, y2 = map(int, boxes.xyxy[0][:4]) + cls_pred = boxes.cls[0] + tmp_image = cv2.rectangle(tmp_image, (x1, y1), (x2, y2), (0, 255, 0), 3) + tmp_image = cv2.putText(tmp_image, names[cls_pred], (x1, y1), cv2.FONT_HERSHEY_SIMPLEX, 1.0, (0, 255, 0), 2) depth_mask[y1:y2, x1:x2] = 1 - - tmp_rgb_image = cv2.cvtColor(tmp_rgb_image, cv2.COLOR_RGB2BGR) - detection_result = self.bridge.cv2_to_imgmsg(tmp_rgb_image, "bgr8") + + # publish image + detection_result = self.bridge.cv2_to_imgmsg(tmp_image, "bgr8") self.detection_result_pub.publish(detection_result) masked_depth = np.where(depth_mask, tmp_depth_image, 0) @@ -87,4 +84,4 @@ def process(self): try: dd.process() except rospy.ROSInitException: - pass \ No newline at end of file + pass From e563b905f462634783f208adbd276d0625270fe3 Mon Sep 17 00:00:00 2001 From: hellososhi <22724971+hellososhi@users.noreply.github.com> Date: Fri, 4 Aug 2023 19:29:35 +0900 Subject: [PATCH 5/8] =?UTF-8?q?BGR2RGB=20=E3=82=92=E6=B6=88=E3=81=99?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../src/three-dimensions_tutorial/scripts/detection_mask.py | 1 - 1 file changed, 1 deletion(-) diff --git a/catkin_ws/src/three-dimensions_tutorial/scripts/detection_mask.py b/catkin_ws/src/three-dimensions_tutorial/scripts/detection_mask.py index 76c7f36..683dff6 100755 --- a/catkin_ws/src/three-dimensions_tutorial/scripts/detection_mask.py +++ b/catkin_ws/src/three-dimensions_tutorial/scripts/detection_mask.py @@ -34,7 +34,6 @@ def __init__(self): def callback_rgbd(self, data1, data2, data3): cv_array = self.bridge.imgmsg_to_cv2(data1, 'bgr8') - cv_array = cv2.cvtColor(cv_array, cv2.COLOR_BGR2RGB) self.rgb_image = cv_array cv_array = self.bridge.imgmsg_to_cv2(data2, 'passthrough') From 421c8beaede286303472661cf9476d07b3aafe9e Mon Sep 17 00:00:00 2001 From: hellososhi <22724971+hellososhi@users.noreply.github.com> Date: Fri, 4 Aug 2023 19:30:52 +0900 Subject: [PATCH 6/8] =?UTF-8?q?=E9=87=8D=E8=A4=87=E3=81=97=E3=81=9F?= =?UTF-8?q?=E5=A4=89=E6=95=B0?= MIME-Version: 1.0 Content-Type: text/plain; charset=UTF-8 Content-Transfer-Encoding: 8bit --- .../three-dimensions_tutorial/scripts/detection_mask.py | 8 +++----- 1 file changed, 3 insertions(+), 5 deletions(-) diff --git a/catkin_ws/src/three-dimensions_tutorial/scripts/detection_mask.py b/catkin_ws/src/three-dimensions_tutorial/scripts/detection_mask.py index 683dff6..47c7373 100755 --- a/catkin_ws/src/three-dimensions_tutorial/scripts/detection_mask.py +++ b/catkin_ws/src/three-dimensions_tutorial/scripts/detection_mask.py @@ -54,8 +54,6 @@ def process(self): results: List[Results] = self.model.predict(self.rgb_image) - # plot bounding box - tmp_image = copy.deepcopy(self.rgb_image) for result in results: boxes = result.boxes.cpu().numpy() names = result.names @@ -63,12 +61,12 @@ def process(self): continue x1, y1, x2, y2 = map(int, boxes.xyxy[0][:4]) cls_pred = boxes.cls[0] - tmp_image = cv2.rectangle(tmp_image, (x1, y1), (x2, y2), (0, 255, 0), 3) - tmp_image = cv2.putText(tmp_image, names[cls_pred], (x1, y1), cv2.FONT_HERSHEY_SIMPLEX, 1.0, (0, 255, 0), 2) + tmp_rgb_image = cv2.rectangle(tmp_rgb_image, (x1, y1), (x2, y2), (0, 255, 0), 3) + tmp_rgb_image = cv2.putText(tmp_rgb_image, names[cls_pred], (x1, y1), cv2.FONT_HERSHEY_SIMPLEX, 1.0, (0, 255, 0), 2) depth_mask[y1:y2, x1:x2] = 1 # publish image - detection_result = self.bridge.cv2_to_imgmsg(tmp_image, "bgr8") + detection_result = self.bridge.cv2_to_imgmsg(tmp_rgb_image, "bgr8") self.detection_result_pub.publish(detection_result) masked_depth = np.where(depth_mask, tmp_depth_image, 0) From bb116b4639687aa808ee85a236f11af26f17cdfb Mon Sep 17 00:00:00 2001 From: hellososhi <22724971+hellososhi@users.noreply.github.com> Date: Fri, 4 Aug 2023 19:54:05 +0900 Subject: [PATCH 7/8] detection_distance.py --- .../scripts/detection_distance.py | 47 +++++++++---------- 1 file changed, 23 insertions(+), 24 deletions(-) diff --git a/catkin_ws/src/three-dimensions_tutorial/scripts/detection_distance.py b/catkin_ws/src/three-dimensions_tutorial/scripts/detection_distance.py index 9ddc356..99f3182 100755 --- a/catkin_ws/src/three-dimensions_tutorial/scripts/detection_distance.py +++ b/catkin_ws/src/three-dimensions_tutorial/scripts/detection_distance.py @@ -1,14 +1,16 @@ #!/usr/bin/env python3 -import rospy +import copy +from typing import List + +import cv2 import message_filters -from sensor_msgs.msg import Image +import rospy from cv_bridge import CvBridge -from pytorchyolo import detect, models -import matplotlib.pyplot as plt -import matplotlib.patches as patches -import cv2 -import copy +from sensor_msgs.msg import Image +from ultralytics import YOLO +from ultralytics.engine.results import Results + class DetectionDistance: def __init__(self): @@ -25,6 +27,8 @@ def __init__(self): self.bridge = CvBridge() self.rgb_image, self.depth_image = None, None + self.model = YOLO('yolov8n.pt') + def callback_rgbd(self, data1, data2): cv_array = self.bridge.imgmsg_to_cv2(data1, 'bgr8') cv_array = cv2.cvtColor(cv_array, cv2.COLOR_BGR2RGB) @@ -34,33 +38,28 @@ def callback_rgbd(self, data1, data2): self.depth_image = cv_array def process(self): - path = "/root/roomba_hack/catkin_ws/src/three-dimensions_tutorial/yolov3/" - - # load category - with open(path+"data/coco.names") as f: - category = f.read().splitlines() - - # prepare model - model = models.load_model(path+"config/yolov3.cfg", path+"weights/yolov3.weights") - while not rospy.is_shutdown(): if self.rgb_image is None: continue # inference tmp_image = copy.copy(self.rgb_image) - boxes = detect.detect_image(model, tmp_image) - # [[x1, y1, x2, y2, confidence, class]] + + results: List[Results] = self.model.predict(self.rgb_image, verbose=False) # plot bouding box - for box in boxes: - x1, y1, x2, y2 = map(int, box[:4]) - cls_pred = int(box[5]) + for result in results: + boxes = result.boxes.cpu().numpy() + names = result.names + if len(boxes.xyxy) == 0: + continue + x1, y1, x2, y2 = map(int, boxes.xyxy[0][:4]) + cls_pred = boxes.cls[0] tmp_image = cv2.rectangle(tmp_image, (x1, y1), (x2, y2), (0, 255, 0), 3) - tmp_image = cv2.putText(tmp_image, category[cls_pred], (x1, y1), cv2.FONT_HERSHEY_SIMPLEX, 1.0, (0, 255, 0), 2) + tmp_image = cv2.putText(tmp_image, names[cls_pred], (x1, y1), cv2.FONT_HERSHEY_SIMPLEX, 1.0, (0, 255, 0), 2) cx, cy = (x1+x2)//2, (y1+y2)//2 - print(category[cls_pred], self.depth_image[cy][cx]/1000, "m") - + print(names[cls_pred], self.depth_image[cy][cx]/1000, "m") + # publish image tmp_image = cv2.cvtColor(tmp_image, cv2.COLOR_RGB2BGR) detection_result = self.bridge.cv2_to_imgmsg(tmp_image, "bgr8") From 3f32618b0b929234883f63e93b59a64d0706b968 Mon Sep 17 00:00:00 2001 From: hellososhi <22724971+hellososhi@users.noreply.github.com> Date: Fri, 4 Aug 2023 19:55:48 +0900 Subject: [PATCH 8/8] delete yolov3 --- .../yolov3/config/yolov3.cfg | 788 ------------------ .../yolov3/data/coco.names | 80 -- .../yolov3/weights/download_weights.sh | 7 - 3 files changed, 875 deletions(-) delete mode 100644 catkin_ws/src/three-dimensions_tutorial/yolov3/config/yolov3.cfg delete mode 100644 catkin_ws/src/three-dimensions_tutorial/yolov3/data/coco.names delete mode 100755 catkin_ws/src/three-dimensions_tutorial/yolov3/weights/download_weights.sh diff --git a/catkin_ws/src/three-dimensions_tutorial/yolov3/config/yolov3.cfg b/catkin_ws/src/three-dimensions_tutorial/yolov3/config/yolov3.cfg deleted file mode 100644 index 23e34f2..0000000 --- a/catkin_ws/src/three-dimensions_tutorial/yolov3/config/yolov3.cfg +++ /dev/null @@ -1,788 +0,0 @@ -[net] -# Testing -#batch=1 -#subdivisions=1 -# Training -batch=16 -subdivisions=1 -width=416 -height=416 -channels=3 -momentum=0.9 -decay=0.0005 -angle=0 -saturation = 1.5 -exposure = 1.5 -hue=.1 - -learning_rate=0.0001 -burn_in=1000 -max_batches = 500200 -policy=steps -steps=400000,450000 -scales=.1,.1 - -[convolutional] -batch_normalize=1 -filters=32 -size=3 -stride=1 -pad=1 -activation=leaky - -# Downsample - -[convolutional] -batch_normalize=1 -filters=64 -size=3 -stride=2 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=32 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=64 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -# Downsample - -[convolutional] -batch_normalize=1 -filters=128 -size=3 -stride=2 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=64 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=128 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=64 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=128 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -# Downsample - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=2 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -# Downsample - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=2 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -# Downsample - -[convolutional] -batch_normalize=1 -filters=1024 -size=3 -stride=2 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=1024 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=512 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=1024 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=512 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=1024 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=512 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=1024 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -###################### - -[convolutional] -batch_normalize=1 -filters=512 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=1024 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=1024 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=1024 -activation=leaky - -[convolutional] -size=1 -stride=1 -pad=1 -filters=255 -activation=linear - - -[yolo] -mask = 6,7,8 -anchors = 10,13, 16,30, 33,23, 30,61, 62,45, 59,119, 116,90, 156,198, 373,326 -classes=80 -num=9 -jitter=.3 -ignore_thresh = .7 -truth_thresh = 1 -random=1 - - -[route] -layers = -4 - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[upsample] -stride=2 - -[route] -layers = -1, 61 - - - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=512 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=512 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=512 -activation=leaky - -[convolutional] -size=1 -stride=1 -pad=1 -filters=255 -activation=linear - - -[yolo] -mask = 3,4,5 -anchors = 10,13, 16,30, 33,23, 30,61, 62,45, 59,119, 116,90, 156,198, 373,326 -classes=80 -num=9 -jitter=.3 -ignore_thresh = .7 -truth_thresh = 1 -random=1 - - - -[route] -layers = -4 - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[upsample] -stride=2 - -[route] -layers = -1, 36 - - - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=256 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=256 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=256 -activation=leaky - -[convolutional] -size=1 -stride=1 -pad=1 -filters=255 -activation=linear - - -[yolo] -mask = 0,1,2 -anchors = 10,13, 16,30, 33,23, 30,61, 62,45, 59,119, 116,90, 156,198, 373,326 -classes=80 -num=9 -jitter=.3 -ignore_thresh = .7 -truth_thresh = 1 -random=1 \ No newline at end of file diff --git a/catkin_ws/src/three-dimensions_tutorial/yolov3/data/coco.names b/catkin_ws/src/three-dimensions_tutorial/yolov3/data/coco.names deleted file mode 100644 index 16315f2..0000000 --- a/catkin_ws/src/three-dimensions_tutorial/yolov3/data/coco.names +++ /dev/null @@ -1,80 +0,0 @@ -person -bicycle -car -motorbike -aeroplane -bus -train -truck -boat -traffic light -fire hydrant -stop sign -parking meter -bench -bird -cat -dog -horse -sheep -cow -elephant -bear -zebra -giraffe -backpack -umbrella -handbag -tie -suitcase -frisbee -skis -snowboard -sports ball -kite -baseball bat -baseball glove -skateboard -surfboard -tennis racket -bottle -wine glass -cup -fork -knife -spoon -bowl -banana -apple -sandwich -orange -broccoli -carrot -hot dog -pizza -donut -cake -chair -sofa -pottedplant -bed -diningtable -toilet -tvmonitor -laptop -mouse -remote -keyboard -cell phone -microwave -oven -toaster -sink -refrigerator -book -clock -vase -scissors -teddy bear -hair drier -toothbrush \ No newline at end of file diff --git a/catkin_ws/src/three-dimensions_tutorial/yolov3/weights/download_weights.sh b/catkin_ws/src/three-dimensions_tutorial/yolov3/weights/download_weights.sh deleted file mode 100755 index 9e44705..0000000 --- a/catkin_ws/src/three-dimensions_tutorial/yolov3/weights/download_weights.sh +++ /dev/null @@ -1,7 +0,0 @@ -#!/bin/bash -# Download weights for vanilla YOLOv3 -wget -c "https://pjreddie.com/media/files/yolov3.weights" --header "Referer: pjreddie.com" -# # Download weights for tiny YOLOv3 -wget -c "https://pjreddie.com/media/files/yolov3-tiny.weights" --header "Referer: pjreddie.com" -# Download weights for backbone network -wget -c "https://pjreddie.com/media/files/darknet53.conv.74" --header "Referer: pjreddie.com" \ No newline at end of file