├── .gitignore ├── CMakeLists.txt ├── LICENSE ├── README.md ├── __init__.py ├── launch └── detector.launch ├── msg ├── BoundingBox.msg └── BoundingBoxes.msg ├── package.xml ├── requirements.txt └── src ├── __init__.py ├── detect.py ├── models ├── __init__.py ├── common.py ├── experimental.py ├── export.py ├── hub │ ├── anchors.yaml │ ├── yolov3-spp.yaml │ ├── yolov3-tiny.yaml │ ├── yolov3.yaml │ ├── yolov5-fpn.yaml │ ├── yolov5-p2.yaml │ ├── yolov5-p6.yaml │ ├── yolov5-p7.yaml │ ├── yolov5-panet.yaml │ ├── yolov5l6.yaml │ ├── yolov5m6.yaml │ ├── yolov5s6.yaml │ └── yolov5x6.yaml ├── yolo.py ├── yolov5l.yaml ├── yolov5m.yaml ├── yolov5s.yaml └── yolov5x.yaml └── utils ├── __init__.py ├── activations.py ├── autoanchor.py ├── datasets.py ├── general.py ├── google_app_engine ├── Dockerfile ├── additional_requirements.txt └── app.yaml ├── google_utils.py ├── loss.py ├── metrics.py ├── plots.py ├── torch_utils.py └── wandb_logging ├── __init__.py ├── log_dataset.py └── wandb_utils.py /.gitignore: -------------------------------------------------------------------------------- 1 | *.pyc 2 | *.weights 3 | *.swp 4 | 5 | -------------------------------------------------------------------------------- /CMakeLists.txt: -------------------------------------------------------------------------------- 1 | cmake_minimum_required(VERSION 2.8.12) 2 | project(yolov5_pytorch_ros) 3 | 4 | find_package(catkin REQUIRED 5 | COMPONENTS 6 | geometry_msgs 7 | sensor_msgs 8 | std_msgs 9 | message_generation) 10 | 11 | add_message_files( 12 | FILES 13 | BoundingBox.msg 14 | BoundingBoxes.msg 15 | ) 16 | 17 | generate_messages( 18 | DEPENDENCIES 19 | geometry_msgs 20 | sensor_msgs 21 | std_msgs 22 | ) 23 | 24 | catkin_package() 25 | 26 | include_directories() 27 | -------------------------------------------------------------------------------- /LICENSE: -------------------------------------------------------------------------------- 1 | BSD 3-Clause License 2 | 3 | Copyright (c) 2019, Vasileios Vasilopoulos, Georgios Pavlakos 4 | All rights reserved. 5 | 6 | Redistribution and use in source and binary forms, with or without 7 | modification, are permitted provided that the following conditions are met: 8 | 9 | 1. Redistributions of source code must retain the above copyright notice, this 10 | list of conditions and the following disclaimer. 11 | 12 | 2. Redistributions in binary form must reproduce the above copyright notice, 13 | this list of conditions and the following disclaimer in the documentation 14 | and/or other materials provided with the distribution. 15 | 16 | 3. Neither the name of the copyright holder nor the names of its 17 | contributors may be used to endorse or promote products derived from 18 | this software without specific prior written permission. 19 | 20 | THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" 21 | AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE 22 | IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 23 | DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE 24 | FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL 25 | DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR 26 | SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER 27 | CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, 28 | OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE 29 | OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 30 | -------------------------------------------------------------------------------- /README.md: -------------------------------------------------------------------------------- 1 | # yolov5_pytorch_ros 2 | This package provides a ROS wrapper for YOLOv5 based on [PyTorch-YOLOv5](v). 3 | 4 | **Authors**: Vasileios Vasilopoulos (), Georgios Pavlakos () 5 | **Adapted by**: Raghava Uppuluri 6 | 7 | ## Prerequisites 8 | 1. Have conda installed 9 | 2. Have ROS installed + setup 10 | 11 | ## Quick Start 12 | 13 | 1. Download the prerequisites for this package, navigate to the package folder and run: 14 | ``` 15 | # Ensure your conda environment is activated 16 | conda install -f requirements.txt 17 | ``` 18 | 19 | ## Installation 20 | Clone the repo into your `src` folder of your `catkin_ws`. 21 | ``` 22 | git clone https://github.com/raghavauppuluri13/yolov5_pytorch_ros.git 23 | ``` 24 | 25 | Navigate to your catkin workspace and run: 26 | ``` 27 | catkin build yolov5_pytorch_ros 28 | # adds package to your path 29 | source ~/catkin_ws/devel/setup.bash 30 | ``` 31 | 32 | ## Basic Usage 33 | To maximize portability, create a separate package and launch file. Add your weights into a `weights` folder of that package. 34 | ``` 35 | catkin_create_pkg my_detector 36 | mkdir weights 37 | mkdir launch 38 | # Add weights 39 | # Don't forget to build and source after 40 | ``` 41 | 42 | Then, add the following to `mydetector.launch` in the launch folder: 43 | ```xml 44 | 45 | 46 | 47 | 48 | 49 | 50 | 51 | 52 | 53 | 54 | 55 | 56 | 57 | 58 | 59 | 60 | ``` 61 | 62 | Finally, run the detector: 63 | ``` 64 | roslaunch my_detector mydetector.launch 65 | ``` 66 | ![detector](https://github.com/purdue-arc/wiki/blob/master/wiki/robot-arm/assets/images/obj_det_may_21.png) 67 | > Should get something like this when viewed from rviz 68 | 69 | ### Node parameters 70 | 71 | * **`image_topic`** (string) 72 | 73 | Subscribed camera topic. 74 | 75 | * **`weights_name`** (string) 76 | 77 | Weights to be used from the [models](models) folder. 78 | 79 | * **`publish_image`** (bool) 80 | 81 | Set to true to get the camera image along with the detected bounding boxes, or false otherwise. 82 | 83 | * **`detected_objects_topic`** (string) 84 | 85 | Published topic with the detected bounding boxes. 86 | 87 | * **`detections_image_topic`** (string) 88 | 89 | Published topic with the detected bounding boxes on top of the image. 90 | 91 | * **`confidence`** (float) 92 | 93 | Confidence threshold for detected objects. 94 | 95 | ### Subscribed topics 96 | 97 | * **`image_topic`** (sensor_msgs::Image) 98 | 99 | Subscribed camera topic. 100 | 101 | ### Published topics 102 | 103 | * **`detected_objects_topic`** (yolov3_pytorch_ros::BoundingBoxes) 104 | 105 | Published topic with the detected bounding boxes. 106 | 107 | * **`detections_image_topic`** (sensor_msgs::Image) 108 | 109 | Published topic with the detected bounding boxes on top of the image (only published if `publish_image` is set to true). 110 | 111 | ## Citing 112 | 113 | The YOLO methods used in this software are described in the paper: [You Only Look Once: Unified, Real-Time Object Detection](https://arxiv.org/abs/1506.02640). 114 | 115 | If you are using this package, please add the following citation to your publication: 116 | 117 | @misc{vasilopoulos_pavlakos_yolov3ros_2019, 118 | author = {Vasileios Vasilopoulos and Georgios Pavlakos}, 119 | title = {{yolov3_pytorch_ros}: Object Detection for {ROS} using {PyTorch}}, 120 | howpublished = {\url{https://github.com/vvasilo/yolov3_pytorch_ros}}, 121 | year = {2019}, 122 | } 123 | -------------------------------------------------------------------------------- /__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/raghavauppuluri13/yolov5_pytorch_ros/fbd8c5d8aa5bcead2ff02445909624924ceb2026/__init__.py -------------------------------------------------------------------------------- /launch/detector.launch: -------------------------------------------------------------------------------- 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 | -------------------------------------------------------------------------------- /msg/BoundingBox.msg: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2017, Marko Bjelonic, Robotic Systems Lab, ETH Zurich 2 | # All rights reserved. 3 | 4 | # Redistribution and use in source and binary forms, with or without 5 | # modification, are permitted provided that the following conditions are met: 6 | # * Redistributions of source code must retain the above copyright 7 | # notice, this list of conditions and the following disclaimer. 8 | # * Redistributions in binary form must reproduce the above copyright 9 | # notice, this list of conditions and the following disclaimer in the 10 | # documentation and/or other materials provided with the distribution. 11 | # * Neither the name of the copyright holder nor the names of its 12 | # contributors may be used to endorse or promote products derived 13 | # from this software without specific prior written permission. 14 | 15 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 16 | # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 17 | # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 18 | # DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY 19 | # DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 20 | # (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 21 | # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 22 | # ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 23 | # (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 24 | # SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 25 | 26 | string Class 27 | float64 probability 28 | int64 xmin 29 | int64 ymin 30 | int64 xmax 31 | int64 ymax 32 | 33 | -------------------------------------------------------------------------------- /msg/BoundingBoxes.msg: -------------------------------------------------------------------------------- 1 | # Copyright (c) 2017, Marko Bjelonic, Robotic Systems Lab, ETH Zurich 2 | # All rights reserved. 3 | 4 | # Redistribution and use in source and binary forms, with or without 5 | # modification, are permitted provided that the following conditions are met: 6 | # * Redistributions of source code must retain the above copyright 7 | # notice, this list of conditions and the following disclaimer. 8 | # * Redistributions in binary form must reproduce the above copyright 9 | # notice, this list of conditions and the following disclaimer in the 10 | # documentation and/or other materials provided with the distribution. 11 | # * Neither the name of the copyright holder nor the names of its 12 | # contributors may be used to endorse or promote products derived 13 | # from this software without specific prior written permission. 14 | 15 | # THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS" AND 16 | # ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE IMPLIED 17 | # WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE 18 | # DISCLAIMED. IN NO EVENT SHALL COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE FOR ANY 19 | # DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES 20 | # (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES; 21 | # LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER CAUSED AND 22 | # ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY, OR TORT 23 | # (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE OF THIS 24 | # SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE. 25 | 26 | Header header 27 | Header image_header 28 | BoundingBox[] bounding_boxes 29 | -------------------------------------------------------------------------------- /package.xml: -------------------------------------------------------------------------------- 1 | 2 | 3 | yolov5_pytorch_ros 4 | 0.1.0 5 | The YOLOv3 PyTorch ROS wrapper package 6 | 7 | Vasileios Vasilopoulos 8 | Georgios Pavlakos 9 | 10 | BSD 11 | 12 | catkin 13 | message_generation 14 | rospy 15 | sensor_msgs 16 | geometry_msgs 17 | std_msgs 18 | cv_bridge 19 | message_runtime 20 | 21 | 22 | -------------------------------------------------------------------------------- /requirements.txt: -------------------------------------------------------------------------------- 1 | # pip install -r requirements.txt 2 | 3 | # base ---------------------------------------- 4 | Cython 5 | matplotlib>=3.2.2 6 | numpy>=1.18.5 7 | opencv-python>=4.1.2 8 | Pillow 9 | PyYAML>=5.3.1 10 | scipy>=1.4.1 11 | scikit-image 12 | tensorboard>=2.2 13 | torch>=1.7.0 14 | torchvision>=0.8.1 15 | tqdm>=4.41.0 16 | 17 | # logging ------------------------------------- 18 | # wandb 19 | 20 | # plotting ------------------------------------ 21 | seaborn>=0.11.0 22 | pandas 23 | 24 | # export -------------------------------------- 25 | # coremltools>=4.1 26 | # onnx>=1.8.1 27 | # scikit-learn==0.19.2 # for coreml quantization 28 | 29 | # extras -------------------------------------- 30 | thop # FLOPS computation 31 | pycocotools>=2.0 # COCO mAP 32 | -------------------------------------------------------------------------------- /src/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/raghavauppuluri13/yolov5_pytorch_ros/fbd8c5d8aa5bcead2ff02445909624924ceb2026/src/__init__.py -------------------------------------------------------------------------------- /src/detect.py: -------------------------------------------------------------------------------- 1 | #!/usr/bin/env python3 2 | 3 | import os 4 | 5 | os.environ['KMP_DUPLICATE_LIB_OK'] = 'True' 6 | 7 | 8 | # Python imports 9 | import numpy as np 10 | import cv2 11 | 12 | # ROS imports 13 | import rospy 14 | import scipy.io as sio 15 | import std_msgs.msg 16 | # Deep Learning imports 17 | import torch 18 | import yaml 19 | from cv_bridge import CvBridge, CvBridgeError 20 | from geometry_msgs.msg import Point32, Polygon 21 | from numpy import random 22 | from rospkg import RosPack 23 | from sensor_msgs.msg import Image 24 | from skimage.transform import resize 25 | from std_msgs.msg import UInt8 26 | from torch.autograd import Variable 27 | from yolov5_pytorch_ros.msg import BoundingBox, BoundingBoxes 28 | 29 | from models.experimental import attempt_load 30 | from utils.datasets import LoadImages, LoadStreams 31 | from utils.general import (apply_classifier, check_img_size, 32 | check_requirements, increment_path, 33 | non_max_suppression, scale_coords, set_logging, 34 | strip_optimizer) 35 | from utils.plots import plot_one_box 36 | # util + model imports 37 | from utils.torch_utils import load_classifier, select_device, time_synchronized 38 | 39 | package = RosPack() 40 | package_path = package.get_path('yolov5_pytorch_ros') 41 | 42 | 43 | class Detector: 44 | def __init__(self): 45 | # Load weights parameter 46 | self.weights_path = rospy.get_param('~weights_path') 47 | rospy.loginfo("Found weights, loading %s", self.weights_path) 48 | 49 | # Raise error if it cannot find the model 50 | if not os.path.isfile(self.weights_path): 51 | raise IOError(('{:s} not found.').format(self.weights_path)) 52 | 53 | # Load image parameter and confidence threshold 54 | self.image_topic = rospy.get_param( 55 | '~image_topic', '/camera/rgb/image_raw') 56 | 57 | log_str = "Subscribing to image topic: %s" % self.image_topic 58 | rospy.loginfo(log_str) 59 | 60 | self.conf_thres = rospy.get_param('~confidence', 0.5) 61 | 62 | # Load other parameters 63 | self.device_name = 'cpu' 64 | self.device = select_device(self.device_name) 65 | self.gpu_id = rospy.get_param('~gpu_id', 0) 66 | self.network_img_size = rospy.get_param('~img_size', 416) 67 | self.publish_image = rospy.get_param('~publish_image') 68 | self.iou_thres = 0.45 69 | self.augment = True 70 | 71 | self.classes = None 72 | self.agnostic_nms = False 73 | 74 | self.w = 0 75 | self.h = 0 76 | 77 | # Second-stage classifier 78 | self.classify = False 79 | 80 | # Initialize 81 | self.half = self.device.type != 'cpu' # half precision only supported on CUDA 82 | 83 | # Load model 84 | self.model = attempt_load( 85 | self.weights_path, map_location=self.device) # load FP32 model 86 | self.stride = int(self.model.stride.max()) # model stride 87 | self.network_img_size = check_img_size( 88 | self.network_img_size, s=self.stride) # check img_size 89 | 90 | if self.half: 91 | self.model.half() # to FP16 92 | 93 | if self.classify: 94 | self.modelc = load_classifier(name='resnet101', n=2) # initialize 95 | self.modelc.load_state_dict(torch.load( 96 | 'weights/resnet101.pt', map_location=self.device)['model']).to(self.device).eval() 97 | 98 | # Get names and colors 99 | self.names = self.model.module.names if hasattr( 100 | self.model, 'module') else self.model.names 101 | self.colors = [[random.randint(0, 255) 102 | for _ in range(3)] for _ in self.names] 103 | 104 | # Run inference 105 | if self.device.type != 'cpu': 106 | self.model(torch.zeros(1, 3, self.network_img_size, self.network_img_size).to( 107 | self.device).type_as(next(self.model.parameters()))) # run once 108 | 109 | # Load CvBridge 110 | self.bridge = CvBridge() 111 | 112 | # Load publisher topic 113 | self.detected_objects_topic = rospy.get_param( 114 | '~detected_objects_topic') 115 | self.published_image_topic = rospy.get_param('~detections_image_topic') 116 | 117 | # Define subscribers 118 | self.image_sub = rospy.Subscriber( 119 | self.image_topic, Image, self.image_cb, queue_size=1, buff_size=2**24) 120 | 121 | # Define publishers 122 | self.pub_ = rospy.Publisher( 123 | self.detected_objects_topic, BoundingBoxes, queue_size=10) 124 | self.pub_viz_ = rospy.Publisher( 125 | self.published_image_topic, Image, queue_size=10) 126 | rospy.loginfo("Launched node for object detection") 127 | 128 | # Spin 129 | rospy.spin() 130 | 131 | def image_cb(self, data): 132 | # Convert the image to OpenCV 133 | try: 134 | self.cv_img = self.bridge.imgmsg_to_cv2(data, "rgb8") 135 | except CvBridgeError as e: 136 | print(e) 137 | # Initialize detection results 138 | 139 | detection_results = BoundingBoxes() 140 | detection_results.header = data.header 141 | detection_results.image_header = data.header 142 | input_img = self.preprocess(self.cv_img) 143 | input_img = Variable(input_img.type(torch.FloatTensor)) 144 | 145 | # Get detections from network 146 | with torch.no_grad(): 147 | detections = self.model(input_img)[0] 148 | detections = non_max_suppression(detections, self.conf_thres, self.iou_thres, 149 | classes=self.classes, agnostic=self.agnostic_nms) 150 | # Parse detections 151 | if detections[0] is not None: 152 | for detection in detections[0]: 153 | # Get xmin, ymin, xmax, ymax, confidence and class 154 | xmin, ymin, xmax, ymax, conf, det_class = detection 155 | pad_x = max(self.h - self.w, 0) * \ 156 | (self.network_img_size/max(self.h, self.w)) 157 | pad_y = max(self.w - self.h, 0) * \ 158 | (self.network_img_size/max(self.h, self.w)) 159 | unpad_h = self.network_img_size-pad_y 160 | unpad_w = self.network_img_size-pad_x 161 | xmin_unpad = ((xmin-pad_x//2)/unpad_w)*self.w 162 | xmax_unpad = ((xmax-xmin)/unpad_w)*self.w + xmin_unpad 163 | ymin_unpad = ((ymin-pad_y//2)/unpad_h)*self.h 164 | ymax_unpad = ((ymax-ymin)/unpad_h)*self.h + ymin_unpad 165 | 166 | # Populate darknet message 167 | detection_msg = BoundingBox() 168 | detection_msg.xmin = int(xmin_unpad) 169 | detection_msg.xmax = int(xmax_unpad) 170 | detection_msg.ymin = int(ymin_unpad) 171 | detection_msg.ymax = int(ymax_unpad) 172 | detection_msg.probability = float(conf) 173 | detection_msg.Class = self.names[int(det_class)] 174 | 175 | # Append in overall detection message 176 | detection_results.bounding_boxes.append(detection_msg) 177 | 178 | # Publish detection results 179 | self.pub_.publish(detection_results) 180 | 181 | # Visualize detection results 182 | if (self.publish_image): 183 | self.visualize_and_publish(detection_results, self.cv_img) 184 | return True 185 | 186 | def preprocess(self, img): 187 | # Extract image and shape 188 | img = np.copy(img) 189 | img = img.astype(float) 190 | height, width, channels = img.shape 191 | if (height != self.h) or (width != self.w): 192 | self.h = height 193 | self.w = width 194 | # Determine image to be used 195 | self.padded_image = np.zeros( 196 | (max(self.h, self.w), max(self.h, self.w), channels)).astype(float) 197 | 198 | # Add padding 199 | if (self.w > self.h): 200 | self.padded_image[(self.w-self.h)//2: self.h + 201 | (self.w-self.h)//2, :, :] = img 202 | else: 203 | self.padded_image[:, (self.h-self.w)//2: self.w + 204 | (self.h-self.w)//2, :] = img 205 | # Resize and normalize 206 | input_img = resize(self.padded_image, (self.network_img_size, self.network_img_size, 3))/255. 207 | 208 | # Channels-first 209 | input_img = np.transpose(input_img, (2, 0, 1)) 210 | 211 | # As pytorch tensor 212 | input_img = torch.from_numpy(input_img).float() 213 | input_img = input_img[None] 214 | 215 | return input_img 216 | 217 | def visualize_and_publish(self, output, imgIn): 218 | # Copy image and visualize 219 | imgOut = imgIn.copy() 220 | font = cv2.FONT_HERSHEY_SIMPLEX 221 | fontScale = 0.8 222 | thickness = 2 223 | for index in range(len(output.bounding_boxes)): 224 | label = output.bounding_boxes[index].Class 225 | x_p1 = output.bounding_boxes[index].xmin 226 | y_p1 = output.bounding_boxes[index].ymin 227 | x_p3 = output.bounding_boxes[index].xmax 228 | y_p3 = output.bounding_boxes[index].ymax 229 | confidence = output.bounding_boxes[index].probability 230 | 231 | # Set class color 232 | color = self.colors[self.names.index(label)] 233 | 234 | # Create rectangle 235 | cv2.rectangle(imgOut, (int(x_p1), int(y_p1)), (int(x_p3), int( 236 | y_p3)), (color[0], color[1], color[2]), thickness) 237 | text = ('{:s}: {:.3f}').format(label, confidence) 238 | cv2.putText(imgOut, text, (int(x_p1), int(y_p1+20)), font, 239 | fontScale, (255, 255, 255), thickness, cv2.LINE_AA) 240 | 241 | # Publish visualization image 242 | image_msg = self.bridge.cv2_to_imgmsg(imgOut, "rgb8") 243 | image_msg.header.frame_id = 'camera' 244 | image_msg.header.stamp = rospy.Time.now() 245 | self.pub_viz_.publish(image_msg) 246 | 247 | 248 | if __name__ == '__main__': 249 | rospy.init_node('detector') 250 | 251 | # Define detector object 252 | dm = Detector() 253 | -------------------------------------------------------------------------------- /src/models/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/raghavauppuluri13/yolov5_pytorch_ros/fbd8c5d8aa5bcead2ff02445909624924ceb2026/src/models/__init__.py -------------------------------------------------------------------------------- /src/models/common.py: -------------------------------------------------------------------------------- 1 | # This file contains modules common to various models 2 | 3 | import math 4 | from pathlib import Path 5 | 6 | import numpy as np 7 | import requests 8 | import torch 9 | import torch.nn as nn 10 | from PIL import Image, ImageDraw 11 | 12 | from utils.datasets import letterbox 13 | from utils.general import non_max_suppression, make_divisible, scale_coords, xyxy2xywh 14 | from utils.plots import color_list 15 | 16 | 17 | def autopad(k, p=None): # kernel, padding 18 | # Pad to 'same' 19 | if p is None: 20 | p = k // 2 if isinstance(k, int) else [x // 2 for x in k] # auto-pad 21 | return p 22 | 23 | 24 | def DWConv(c1, c2, k=1, s=1, act=True): 25 | # Depthwise convolution 26 | return Conv(c1, c2, k, s, g=math.gcd(c1, c2), act=act) 27 | 28 | 29 | class Conv(nn.Module): 30 | # Standard convolution 31 | def __init__(self, c1, c2, k=1, s=1, p=None, g=1, act=True): # ch_in, ch_out, kernel, stride, padding, groups 32 | super(Conv, self).__init__() 33 | self.conv = nn.Conv2d(c1, c2, k, s, autopad(k, p), groups=g, bias=False) 34 | self.bn = nn.BatchNorm2d(c2) 35 | self.act = nn.SiLU() if act is True else (act if isinstance(act, nn.Module) else nn.Identity()) 36 | 37 | def forward(self, x): 38 | return self.act(self.bn(self.conv(x))) 39 | 40 | def fuseforward(self, x): 41 | return self.act(self.conv(x)) 42 | 43 | 44 | class Bottleneck(nn.Module): 45 | # Standard bottleneck 46 | def __init__(self, c1, c2, shortcut=True, g=1, e=0.5): # ch_in, ch_out, shortcut, groups, expansion 47 | super(Bottleneck, self).__init__() 48 | c_ = int(c2 * e) # hidden channels 49 | self.cv1 = Conv(c1, c_, 1, 1) 50 | self.cv2 = Conv(c_, c2, 3, 1, g=g) 51 | self.add = shortcut and c1 == c2 52 | 53 | def forward(self, x): 54 | return x + self.cv2(self.cv1(x)) if self.add else self.cv2(self.cv1(x)) 55 | 56 | 57 | class BottleneckCSP(nn.Module): 58 | # CSP Bottleneck https://github.com/WongKinYiu/CrossStagePartialNetworks 59 | def __init__(self, c1, c2, n=1, shortcut=True, g=1, e=0.5): # ch_in, ch_out, number, shortcut, groups, expansion 60 | super(BottleneckCSP, self).__init__() 61 | c_ = int(c2 * e) # hidden channels 62 | self.cv1 = Conv(c1, c_, 1, 1) 63 | self.cv2 = nn.Conv2d(c1, c_, 1, 1, bias=False) 64 | self.cv3 = nn.Conv2d(c_, c_, 1, 1, bias=False) 65 | self.cv4 = Conv(2 * c_, c2, 1, 1) 66 | self.bn = nn.BatchNorm2d(2 * c_) # applied to cat(cv2, cv3) 67 | self.act = nn.LeakyReLU(0.1, inplace=True) 68 | self.m = nn.Sequential(*[Bottleneck(c_, c_, shortcut, g, e=1.0) for _ in range(n)]) 69 | 70 | def forward(self, x): 71 | y1 = self.cv3(self.m(self.cv1(x))) 72 | y2 = self.cv2(x) 73 | return self.cv4(self.act(self.bn(torch.cat((y1, y2), dim=1)))) 74 | 75 | 76 | class C3(nn.Module): 77 | # CSP Bottleneck with 3 convolutions 78 | def __init__(self, c1, c2, n=1, shortcut=True, g=1, e=0.5): # ch_in, ch_out, number, shortcut, groups, expansion 79 | super(C3, self).__init__() 80 | c_ = int(c2 * e) # hidden channels 81 | self.cv1 = Conv(c1, c_, 1, 1) 82 | self.cv2 = Conv(c1, c_, 1, 1) 83 | self.cv3 = Conv(2 * c_, c2, 1) # act=FReLU(c2) 84 | self.m = nn.Sequential(*[Bottleneck(c_, c_, shortcut, g, e=1.0) for _ in range(n)]) 85 | # self.m = nn.Sequential(*[CrossConv(c_, c_, 3, 1, g, 1.0, shortcut) for _ in range(n)]) 86 | 87 | def forward(self, x): 88 | return self.cv3(torch.cat((self.m(self.cv1(x)), self.cv2(x)), dim=1)) 89 | 90 | 91 | class SPP(nn.Module): 92 | # Spatial pyramid pooling layer used in YOLOv3-SPP 93 | def __init__(self, c1, c2, k=(5, 9, 13)): 94 | super(SPP, self).__init__() 95 | c_ = c1 // 2 # hidden channels 96 | self.cv1 = Conv(c1, c_, 1, 1) 97 | self.cv2 = Conv(c_ * (len(k) + 1), c2, 1, 1) 98 | self.m = nn.ModuleList([nn.MaxPool2d(kernel_size=x, stride=1, padding=x // 2) for x in k]) 99 | 100 | def forward(self, x): 101 | x = self.cv1(x) 102 | return self.cv2(torch.cat([x] + [m(x) for m in self.m], 1)) 103 | 104 | 105 | class Focus(nn.Module): 106 | # Focus wh information into c-space 107 | def __init__(self, c1, c2, k=1, s=1, p=None, g=1, act=True): # ch_in, ch_out, kernel, stride, padding, groups 108 | super(Focus, self).__init__() 109 | self.conv = Conv(c1 * 4, c2, k, s, p, g, act) 110 | # self.contract = Contract(gain=2) 111 | 112 | def forward(self, x): # x(b,c,w,h) -> y(b,4c,w/2,h/2) 113 | return self.conv(torch.cat([x[..., ::2, ::2], x[..., 1::2, ::2], x[..., ::2, 1::2], x[..., 1::2, 1::2]], 1)) 114 | # return self.conv(self.contract(x)) 115 | 116 | 117 | class Contract(nn.Module): 118 | # Contract width-height into channels, i.e. x(1,64,80,80) to x(1,256,40,40) 119 | def __init__(self, gain=2): 120 | super().__init__() 121 | self.gain = gain 122 | 123 | def forward(self, x): 124 | N, C, H, W = x.size() # assert (H / s == 0) and (W / s == 0), 'Indivisible gain' 125 | s = self.gain 126 | x = x.view(N, C, H // s, s, W // s, s) # x(1,64,40,2,40,2) 127 | x = x.permute(0, 3, 5, 1, 2, 4).contiguous() # x(1,2,2,64,40,40) 128 | return x.view(N, C * s * s, H // s, W // s) # x(1,256,40,40) 129 | 130 | 131 | class Expand(nn.Module): 132 | # Expand channels into width-height, i.e. x(1,64,80,80) to x(1,16,160,160) 133 | def __init__(self, gain=2): 134 | super().__init__() 135 | self.gain = gain 136 | 137 | def forward(self, x): 138 | N, C, H, W = x.size() # assert C / s ** 2 == 0, 'Indivisible gain' 139 | s = self.gain 140 | x = x.view(N, s, s, C // s ** 2, H, W) # x(1,2,2,16,80,80) 141 | x = x.permute(0, 3, 4, 1, 5, 2).contiguous() # x(1,16,80,2,80,2) 142 | return x.view(N, C // s ** 2, H * s, W * s) # x(1,16,160,160) 143 | 144 | 145 | class Concat(nn.Module): 146 | # Concatenate a list of tensors along dimension 147 | def __init__(self, dimension=1): 148 | super(Concat, self).__init__() 149 | self.d = dimension 150 | 151 | def forward(self, x): 152 | return torch.cat(x, self.d) 153 | 154 | 155 | class NMS(nn.Module): 156 | # Non-Maximum Suppression (NMS) module 157 | conf = 0.25 # confidence threshold 158 | iou = 0.45 # IoU threshold 159 | classes = None # (optional list) filter by class 160 | 161 | def __init__(self): 162 | super(NMS, self).__init__() 163 | 164 | def forward(self, x): 165 | return non_max_suppression(x[0], conf_thres=self.conf, iou_thres=self.iou, classes=self.classes) 166 | 167 | 168 | class autoShape(nn.Module): 169 | # input-robust model wrapper for passing cv2/np/PIL/torch inputs. Includes preprocessing, inference and NMS 170 | img_size = 640 # inference size (pixels) 171 | conf = 0.25 # NMS confidence threshold 172 | iou = 0.45 # NMS IoU threshold 173 | classes = None # (optional list) filter by class 174 | 175 | def __init__(self, model): 176 | super(autoShape, self).__init__() 177 | self.model = model.eval() 178 | 179 | def autoshape(self): 180 | print('autoShape already enabled, skipping... ') # model already converted to model.autoshape() 181 | return self 182 | 183 | def forward(self, imgs, size=640, augment=False, profile=False): 184 | # Inference from various sources. For height=720, width=1280, RGB images example inputs are: 185 | # filename: imgs = 'data/samples/zidane.jpg' 186 | # URI: = 'https://github.com/ultralytics/yolov5/releases/download/v1.0/zidane.jpg' 187 | # OpenCV: = cv2.imread('image.jpg')[:,:,::-1] # HWC BGR to RGB x(720,1280,3) 188 | # PIL: = Image.open('image.jpg') # HWC x(720,1280,3) 189 | # numpy: = np.zeros((720,1280,3)) # HWC 190 | # torch: = torch.zeros(16,3,720,1280) # BCHW 191 | # multiple: = [Image.open('image1.jpg'), Image.open('image2.jpg'), ...] # list of images 192 | 193 | p = next(self.model.parameters()) # for device and type 194 | if isinstance(imgs, torch.Tensor): # torch 195 | return self.model(imgs.to(p.device).type_as(p), augment, profile) # inference 196 | 197 | # Pre-process 198 | n, imgs = (len(imgs), imgs) if isinstance(imgs, list) else (1, [imgs]) # number of images, list of images 199 | shape0, shape1, files = [], [], [] # image and inference shapes, filenames 200 | for i, im in enumerate(imgs): 201 | if isinstance(im, str): # filename or uri 202 | im = Image.open(requests.get(im, stream=True).raw if im.startswith('http') else im) # open 203 | files.append(Path(im.filename).with_suffix('.jpg').name if isinstance(im, Image.Image) else f'image{i}.jpg') 204 | im = np.array(im) # to numpy 205 | if im.shape[0] < 5: # image in CHW 206 | im = im.transpose((1, 2, 0)) # reverse dataloader .transpose(2, 0, 1) 207 | im = im[:, :, :3] if im.ndim == 3 else np.tile(im[:, :, None], 3) # enforce 3ch input 208 | s = im.shape[:2] # HWC 209 | shape0.append(s) # image shape 210 | g = (size / max(s)) # gain 211 | shape1.append([y * g for y in s]) 212 | imgs[i] = im # update 213 | shape1 = [make_divisible(x, int(self.stride.max())) for x in np.stack(shape1, 0).max(0)] # inference shape 214 | x = [letterbox(im, new_shape=shape1, auto=False)[0] for im in imgs] # pad 215 | x = np.stack(x, 0) if n > 1 else x[0][None] # stack 216 | x = np.ascontiguousarray(x.transpose((0, 3, 1, 2))) # BHWC to BCHW 217 | x = torch.from_numpy(x).to(p.device).type_as(p) / 255. # uint8 to fp16/32 218 | 219 | # Inference 220 | with torch.no_grad(): 221 | y = self.model(x, augment, profile)[0] # forward 222 | y = non_max_suppression(y, conf_thres=self.conf, iou_thres=self.iou, classes=self.classes) # NMS 223 | 224 | # Post-process 225 | for i in range(n): 226 | scale_coords(shape1, y[i][:, :4], shape0[i]) 227 | 228 | return Detections(imgs, y, files, self.names) 229 | 230 | 231 | class Detections: 232 | # detections class for YOLOv5 inference results 233 | def __init__(self, imgs, pred, files, names=None): 234 | super(Detections, self).__init__() 235 | d = pred[0].device # device 236 | gn = [torch.tensor([*[im.shape[i] for i in [1, 0, 1, 0]], 1., 1.], device=d) for im in imgs] # normalizations 237 | self.imgs = imgs # list of images as numpy arrays 238 | self.pred = pred # list of tensors pred[0] = (xyxy, conf, cls) 239 | self.names = names # class names 240 | self.files = files # image filenames 241 | self.xyxy = pred # xyxy pixels 242 | self.xywh = [xyxy2xywh(x) for x in pred] # xywh pixels 243 | self.xyxyn = [x / g for x, g in zip(self.xyxy, gn)] # xyxy normalized 244 | self.xywhn = [x / g for x, g in zip(self.xywh, gn)] # xywh normalized 245 | self.n = len(self.pred) 246 | 247 | def display(self, pprint=False, show=False, save=False, render=False, save_dir=''): 248 | colors = color_list() 249 | for i, (img, pred) in enumerate(zip(self.imgs, self.pred)): 250 | str = f'image {i + 1}/{len(self.pred)}: {img.shape[0]}x{img.shape[1]} ' 251 | if pred is not None: 252 | for c in pred[:, -1].unique(): 253 | n = (pred[:, -1] == c).sum() # detections per class 254 | str += f"{n} {self.names[int(c)]}{'s' * (n > 1)}, " # add to string 255 | if show or save or render: 256 | img = Image.fromarray(img.astype(np.uint8)) if isinstance(img, np.ndarray) else img # from np 257 | for *box, conf, cls in pred: # xyxy, confidence, class 258 | # str += '%s %.2f, ' % (names[int(cls)], conf) # label 259 | ImageDraw.Draw(img).rectangle(box, width=4, outline=colors[int(cls) % 10]) # plot 260 | if pprint: 261 | print(str.rstrip(', ')) 262 | if show: 263 | img.show(self.files[i]) # show 264 | if save: 265 | f = Path(save_dir) / self.files[i] 266 | img.save(f) # save 267 | print(f"{'Saving' * (i == 0)} {f},", end='' if i < self.n - 1 else ' done.\n') 268 | if render: 269 | self.imgs[i] = np.asarray(img) 270 | 271 | def print(self): 272 | self.display(pprint=True) # print results 273 | 274 | def show(self): 275 | self.display(show=True) # show results 276 | 277 | def save(self, save_dir='results/'): 278 | Path(save_dir).mkdir(exist_ok=True) 279 | self.display(save=True, save_dir=save_dir) # save results 280 | 281 | def render(self): 282 | self.display(render=True) # render results 283 | return self.imgs 284 | 285 | def __len__(self): 286 | return self.n 287 | 288 | def tolist(self): 289 | # return a list of Detections objects, i.e. 'for result in results.tolist():' 290 | x = [Detections([self.imgs[i]], [self.pred[i]], self.names) for i in range(self.n)] 291 | for d in x: 292 | for k in ['imgs', 'pred', 'xyxy', 'xyxyn', 'xywh', 'xywhn']: 293 | setattr(d, k, getattr(d, k)[0]) # pop out of list 294 | return x 295 | 296 | 297 | class Classify(nn.Module): 298 | # Classification head, i.e. x(b,c1,20,20) to x(b,c2) 299 | def __init__(self, c1, c2, k=1, s=1, p=None, g=1): # ch_in, ch_out, kernel, stride, padding, groups 300 | super(Classify, self).__init__() 301 | self.aap = nn.AdaptiveAvgPool2d(1) # to x(b,c1,1,1) 302 | self.conv = nn.Conv2d(c1, c2, k, s, autopad(k, p), groups=g) # to x(b,c2,1,1) 303 | self.flat = nn.Flatten() 304 | 305 | def forward(self, x): 306 | z = torch.cat([self.aap(y) for y in (x if isinstance(x, list) else [x])], 1) # cat if list 307 | return self.flat(self.conv(z)) # flatten to x(b,c2) 308 | -------------------------------------------------------------------------------- /src/models/experimental.py: -------------------------------------------------------------------------------- 1 | # This file contains experimental modules 2 | 3 | import numpy as np 4 | import torch 5 | import torch.nn as nn 6 | 7 | from models.common import Conv, DWConv 8 | from utils.google_utils import attempt_download 9 | 10 | 11 | class CrossConv(nn.Module): 12 | # Cross Convolution Downsample 13 | def __init__(self, c1, c2, k=3, s=1, g=1, e=1.0, shortcut=False): 14 | # ch_in, ch_out, kernel, stride, groups, expansion, shortcut 15 | super(CrossConv, self).__init__() 16 | c_ = int(c2 * e) # hidden channels 17 | self.cv1 = Conv(c1, c_, (1, k), (1, s)) 18 | self.cv2 = Conv(c_, c2, (k, 1), (s, 1), g=g) 19 | self.add = shortcut and c1 == c2 20 | 21 | def forward(self, x): 22 | return x + self.cv2(self.cv1(x)) if self.add else self.cv2(self.cv1(x)) 23 | 24 | 25 | class Sum(nn.Module): 26 | # Weighted sum of 2 or more layers https://arxiv.org/abs/1911.09070 27 | def __init__(self, n, weight=False): # n: number of inputs 28 | super(Sum, self).__init__() 29 | self.weight = weight # apply weights boolean 30 | self.iter = range(n - 1) # iter object 31 | if weight: 32 | self.w = nn.Parameter(-torch.arange(1., n) / 2, requires_grad=True) # layer weights 33 | 34 | def forward(self, x): 35 | y = x[0] # no weight 36 | if self.weight: 37 | w = torch.sigmoid(self.w) * 2 38 | for i in self.iter: 39 | y = y + x[i + 1] * w[i] 40 | else: 41 | for i in self.iter: 42 | y = y + x[i + 1] 43 | return y 44 | 45 | 46 | class GhostConv(nn.Module): 47 | # Ghost Convolution https://github.com/huawei-noah/ghostnet 48 | def __init__(self, c1, c2, k=1, s=1, g=1, act=True): # ch_in, ch_out, kernel, stride, groups 49 | super(GhostConv, self).__init__() 50 | c_ = c2 // 2 # hidden channels 51 | self.cv1 = Conv(c1, c_, k, s, None, g, act) 52 | self.cv2 = Conv(c_, c_, 5, 1, None, c_, act) 53 | 54 | def forward(self, x): 55 | y = self.cv1(x) 56 | return torch.cat([y, self.cv2(y)], 1) 57 | 58 | 59 | class GhostBottleneck(nn.Module): 60 | # Ghost Bottleneck https://github.com/huawei-noah/ghostnet 61 | def __init__(self, c1, c2, k=3, s=1): # ch_in, ch_out, kernel, stride 62 | super(GhostBottleneck, self).__init__() 63 | c_ = c2 // 2 64 | self.conv = nn.Sequential(GhostConv(c1, c_, 1, 1), # pw 65 | DWConv(c_, c_, k, s, act=False) if s == 2 else nn.Identity(), # dw 66 | GhostConv(c_, c2, 1, 1, act=False)) # pw-linear 67 | self.shortcut = nn.Sequential(DWConv(c1, c1, k, s, act=False), 68 | Conv(c1, c2, 1, 1, act=False)) if s == 2 else nn.Identity() 69 | 70 | def forward(self, x): 71 | return self.conv(x) + self.shortcut(x) 72 | 73 | 74 | class MixConv2d(nn.Module): 75 | # Mixed Depthwise Conv https://arxiv.org/abs/1907.09595 76 | def __init__(self, c1, c2, k=(1, 3), s=1, equal_ch=True): 77 | super(MixConv2d, self).__init__() 78 | groups = len(k) 79 | if equal_ch: # equal c_ per group 80 | i = torch.linspace(0, groups - 1E-6, c2).floor() # c2 indices 81 | c_ = [(i == g).sum() for g in range(groups)] # intermediate channels 82 | else: # equal weight.numel() per group 83 | b = [c2] + [0] * groups 84 | a = np.eye(groups + 1, groups, k=-1) 85 | a -= np.roll(a, 1, axis=1) 86 | a *= np.array(k) ** 2 87 | a[0] = 1 88 | c_ = np.linalg.lstsq(a, b, rcond=None)[0].round() # solve for equal weight indices, ax = b 89 | 90 | self.m = nn.ModuleList([nn.Conv2d(c1, int(c_[g]), k[g], s, k[g] // 2, bias=False) for g in range(groups)]) 91 | self.bn = nn.BatchNorm2d(c2) 92 | self.act = nn.LeakyReLU(0.1, inplace=True) 93 | 94 | def forward(self, x): 95 | return x + self.act(self.bn(torch.cat([m(x) for m in self.m], 1))) 96 | 97 | 98 | class Ensemble(nn.ModuleList): 99 | # Ensemble of models 100 | def __init__(self): 101 | super(Ensemble, self).__init__() 102 | 103 | def forward(self, x, augment=False): 104 | y = [] 105 | for module in self: 106 | y.append(module(x, augment)[0]) 107 | # y = torch.stack(y).max(0)[0] # max ensemble 108 | # y = torch.stack(y).mean(0) # mean ensemble 109 | y = torch.cat(y, 1) # nms ensemble 110 | return y, None # inference, train output 111 | 112 | 113 | def attempt_load(weights, map_location=None): 114 | # Loads an ensemble of models weights=[a,b,c] or a single model weights=[a] or weights=a 115 | model = Ensemble() 116 | for w in weights if isinstance(weights, list) else [weights]: 117 | attempt_download(w) 118 | model.append(torch.load(w, map_location=map_location)['model'].float().fuse().eval()) # load FP32 model 119 | 120 | # Compatibility updates 121 | for m in model.modules(): 122 | if type(m) in [nn.Hardswish, nn.LeakyReLU, nn.ReLU, nn.ReLU6, nn.SiLU]: 123 | m.inplace = True # pytorch 1.7.0 compatibility 124 | elif type(m) is Conv: 125 | m._non_persistent_buffers_set = set() # pytorch 1.6.0 compatibility 126 | 127 | if len(model) == 1: 128 | return model[-1] # return model 129 | else: 130 | print('Ensemble created with %s\n' % weights) 131 | for k in ['names', 'stride']: 132 | setattr(model, k, getattr(model[-1], k)) 133 | return model # return ensemble 134 | -------------------------------------------------------------------------------- /src/models/export.py: -------------------------------------------------------------------------------- 1 | """Exports a YOLOv5 *.pt model to ONNX and TorchScript formats 2 | 3 | Usage: 4 | $ export PYTHONPATH="$PWD" && python models/export.py --weights ./weights/yolov5s.pt --img 640 --batch 1 5 | """ 6 | 7 | import argparse 8 | import sys 9 | import time 10 | 11 | sys.path.append('./') # to run '$ python *.py' files in subdirectories 12 | 13 | import torch 14 | import torch.nn as nn 15 | 16 | import models 17 | from models.experimental import attempt_load 18 | from utils.activations import Hardswish, SiLU 19 | from utils.general import set_logging, check_img_size 20 | 21 | if __name__ == '__main__': 22 | parser = argparse.ArgumentParser() 23 | parser.add_argument('--weights', type=str, default='./yolov5s.pt', help='weights path') # from yolov5/models/ 24 | parser.add_argument('--img-size', nargs='+', type=int, default=[640, 640], help='image size') # height, width 25 | parser.add_argument('--batch-size', type=int, default=1, help='batch size') 26 | opt = parser.parse_args() 27 | opt.img_size *= 2 if len(opt.img_size) == 1 else 1 # expand 28 | print(opt) 29 | set_logging() 30 | t = time.time() 31 | 32 | # Load PyTorch model 33 | model = attempt_load(opt.weights, map_location=torch.device('cpu')) # load FP32 model 34 | labels = model.names 35 | 36 | # Checks 37 | gs = int(max(model.stride)) # grid size (max stride) 38 | opt.img_size = [check_img_size(x, gs) for x in opt.img_size] # verify img_size are gs-multiples 39 | 40 | # Input 41 | img = torch.zeros(opt.batch_size, 3, *opt.img_size) # image size(1,3,320,192) iDetection 42 | 43 | # Update model 44 | for k, m in model.named_modules(): 45 | m._non_persistent_buffers_set = set() # pytorch 1.6.0 compatibility 46 | if isinstance(m, models.common.Conv): # assign export-friendly activations 47 | if isinstance(m.act, nn.Hardswish): 48 | m.act = Hardswish() 49 | elif isinstance(m.act, nn.SiLU): 50 | m.act = SiLU() 51 | # elif isinstance(m, models.yolo.Detect): 52 | # m.forward = m.forward_export # assign forward (optional) 53 | model.model[-1].export = True # set Detect() layer export=True 54 | y = model(img) # dry run 55 | 56 | # TorchScript export 57 | try: 58 | print('\nStarting TorchScript export with torch %s...' % torch.__version__) 59 | f = opt.weights.replace('.pt', '.torchscript.pt') # filename 60 | ts = torch.jit.trace(model, img) 61 | ts.save(f) 62 | print('TorchScript export success, saved as %s' % f) 63 | except Exception as e: 64 | print('TorchScript export failure: %s' % e) 65 | 66 | # ONNX export 67 | try: 68 | import onnx 69 | 70 | print('\nStarting ONNX export with onnx %s...' % onnx.__version__) 71 | f = opt.weights.replace('.pt', '.onnx') # filename 72 | torch.onnx.export(model, img, f, verbose=False, opset_version=12, input_names=['images'], 73 | output_names=['classes', 'boxes'] if y is None else ['output']) 74 | 75 | # Checks 76 | onnx_model = onnx.load(f) # load onnx model 77 | onnx.checker.check_model(onnx_model) # check onnx model 78 | # print(onnx.helper.printable_graph(onnx_model.graph)) # print a human readable model 79 | print('ONNX export success, saved as %s' % f) 80 | except Exception as e: 81 | print('ONNX export failure: %s' % e) 82 | 83 | # CoreML export 84 | try: 85 | import coremltools as ct 86 | 87 | print('\nStarting CoreML export with coremltools %s...' % ct.__version__) 88 | # convert model from torchscript and apply pixel scaling as per detect.py 89 | model = ct.convert(ts, inputs=[ct.ImageType(name='image', shape=img.shape, scale=1 / 255.0, bias=[0, 0, 0])]) 90 | f = opt.weights.replace('.pt', '.mlmodel') # filename 91 | model.save(f) 92 | print('CoreML export success, saved as %s' % f) 93 | except Exception as e: 94 | print('CoreML export failure: %s' % e) 95 | 96 | # Finish 97 | print('\nExport complete (%.2fs). Visualize with https://github.com/lutzroeder/netron.' % (time.time() - t)) 98 | -------------------------------------------------------------------------------- /src/models/hub/anchors.yaml: -------------------------------------------------------------------------------- 1 | # Default YOLOv5 anchors for COCO data 2 | 3 | 4 | # P5 ------------------------------------------------------------------------------------------------------------------- 5 | # P5-640: 6 | anchors_p5_640: 7 | - [ 10,13, 16,30, 33,23 ] # P3/8 8 | - [ 30,61, 62,45, 59,119 ] # P4/16 9 | - [ 116,90, 156,198, 373,326 ] # P5/32 10 | 11 | 12 | # P6 ------------------------------------------------------------------------------------------------------------------- 13 | # P6-640: thr=0.25: 0.9964 BPR, 5.54 anchors past thr, n=12, img_size=640, metric_all=0.281/0.716-mean/best, past_thr=0.469-mean: 9,11, 21,19, 17,41, 43,32, 39,70, 86,64, 65,131, 134,130, 120,265, 282,180, 247,354, 512,387 14 | anchors_p6_640: 15 | - [ 9,11, 21,19, 17,41 ] # P3/8 16 | - [ 43,32, 39,70, 86,64 ] # P4/16 17 | - [ 65,131, 134,130, 120,265 ] # P5/32 18 | - [ 282,180, 247,354, 512,387 ] # P6/64 19 | 20 | # P6-1280: thr=0.25: 0.9950 BPR, 5.55 anchors past thr, n=12, img_size=1280, metric_all=0.281/0.714-mean/best, past_thr=0.468-mean: 19,27, 44,40, 38,94, 96,68, 86,152, 180,137, 140,301, 303,264, 238,542, 436,615, 739,380, 925,792 21 | anchors_p6_1280: 22 | - [ 19,27, 44,40, 38,94 ] # P3/8 23 | - [ 96,68, 86,152, 180,137 ] # P4/16 24 | - [ 140,301, 303,264, 238,542 ] # P5/32 25 | - [ 436,615, 739,380, 925,792 ] # P6/64 26 | 27 | # P6-1920: thr=0.25: 0.9950 BPR, 5.55 anchors past thr, n=12, img_size=1920, metric_all=0.281/0.714-mean/best, past_thr=0.468-mean: 28,41, 67,59, 57,141, 144,103, 129,227, 270,205, 209,452, 455,396, 358,812, 653,922, 1109,570, 1387,1187 28 | anchors_p6_1920: 29 | - [ 28,41, 67,59, 57,141 ] # P3/8 30 | - [ 144,103, 129,227, 270,205 ] # P4/16 31 | - [ 209,452, 455,396, 358,812 ] # P5/32 32 | - [ 653,922, 1109,570, 1387,1187 ] # P6/64 33 | 34 | 35 | # P7 ------------------------------------------------------------------------------------------------------------------- 36 | # P7-640: thr=0.25: 0.9962 BPR, 6.76 anchors past thr, n=15, img_size=640, metric_all=0.275/0.733-mean/best, past_thr=0.466-mean: 11,11, 13,30, 29,20, 30,46, 61,38, 39,92, 78,80, 146,66, 79,163, 149,150, 321,143, 157,303, 257,402, 359,290, 524,372 37 | anchors_p7_640: 38 | - [ 11,11, 13,30, 29,20 ] # P3/8 39 | - [ 30,46, 61,38, 39,92 ] # P4/16 40 | - [ 78,80, 146,66, 79,163 ] # P5/32 41 | - [ 149,150, 321,143, 157,303 ] # P6/64 42 | - [ 257,402, 359,290, 524,372 ] # P7/128 43 | 44 | # P7-1280: thr=0.25: 0.9968 BPR, 6.71 anchors past thr, n=15, img_size=1280, metric_all=0.273/0.732-mean/best, past_thr=0.463-mean: 19,22, 54,36, 32,77, 70,83, 138,71, 75,173, 165,159, 148,334, 375,151, 334,317, 251,626, 499,474, 750,326, 534,814, 1079,818 45 | anchors_p7_1280: 46 | - [ 19,22, 54,36, 32,77 ] # P3/8 47 | - [ 70,83, 138,71, 75,173 ] # P4/16 48 | - [ 165,159, 148,334, 375,151 ] # P5/32 49 | - [ 334,317, 251,626, 499,474 ] # P6/64 50 | - [ 750,326, 534,814, 1079,818 ] # P7/128 51 | 52 | # P7-1920: thr=0.25: 0.9968 BPR, 6.71 anchors past thr, n=15, img_size=1920, metric_all=0.273/0.732-mean/best, past_thr=0.463-mean: 29,34, 81,55, 47,115, 105,124, 207,107, 113,259, 247,238, 222,500, 563,227, 501,476, 376,939, 749,711, 1126,489, 801,1222, 1618,1227 53 | anchors_p7_1920: 54 | - [ 29,34, 81,55, 47,115 ] # P3/8 55 | - [ 105,124, 207,107, 113,259 ] # P4/16 56 | - [ 247,238, 222,500, 563,227 ] # P5/32 57 | - [ 501,476, 376,939, 749,711 ] # P6/64 58 | - [ 1126,489, 801,1222, 1618,1227 ] # P7/128 59 | -------------------------------------------------------------------------------- /src/models/hub/yolov3-spp.yaml: -------------------------------------------------------------------------------- 1 | # parameters 2 | nc: 80 # number of classes 3 | depth_multiple: 1.0 # model depth multiple 4 | width_multiple: 1.0 # layer channel multiple 5 | 6 | # anchors 7 | anchors: 8 | - [10,13, 16,30, 33,23] # P3/8 9 | - [30,61, 62,45, 59,119] # P4/16 10 | - [116,90, 156,198, 373,326] # P5/32 11 | 12 | # darknet53 backbone 13 | backbone: 14 | # [from, number, module, args] 15 | [[-1, 1, Conv, [32, 3, 1]], # 0 16 | [-1, 1, Conv, [64, 3, 2]], # 1-P1/2 17 | [-1, 1, Bottleneck, [64]], 18 | [-1, 1, Conv, [128, 3, 2]], # 3-P2/4 19 | [-1, 2, Bottleneck, [128]], 20 | [-1, 1, Conv, [256, 3, 2]], # 5-P3/8 21 | [-1, 8, Bottleneck, [256]], 22 | [-1, 1, Conv, [512, 3, 2]], # 7-P4/16 23 | [-1, 8, Bottleneck, [512]], 24 | [-1, 1, Conv, [1024, 3, 2]], # 9-P5/32 25 | [-1, 4, Bottleneck, [1024]], # 10 26 | ] 27 | 28 | # YOLOv3-SPP head 29 | head: 30 | [[-1, 1, Bottleneck, [1024, False]], 31 | [-1, 1, SPP, [512, [5, 9, 13]]], 32 | [-1, 1, Conv, [1024, 3, 1]], 33 | [-1, 1, Conv, [512, 1, 1]], 34 | [-1, 1, Conv, [1024, 3, 1]], # 15 (P5/32-large) 35 | 36 | [-2, 1, Conv, [256, 1, 1]], 37 | [-1, 1, nn.Upsample, [None, 2, 'nearest']], 38 | [[-1, 8], 1, Concat, [1]], # cat backbone P4 39 | [-1, 1, Bottleneck, [512, False]], 40 | [-1, 1, Bottleneck, [512, False]], 41 | [-1, 1, Conv, [256, 1, 1]], 42 | [-1, 1, Conv, [512, 3, 1]], # 22 (P4/16-medium) 43 | 44 | [-2, 1, Conv, [128, 1, 1]], 45 | [-1, 1, nn.Upsample, [None, 2, 'nearest']], 46 | [[-1, 6], 1, Concat, [1]], # cat backbone P3 47 | [-1, 1, Bottleneck, [256, False]], 48 | [-1, 2, Bottleneck, [256, False]], # 27 (P3/8-small) 49 | 50 | [[27, 22, 15], 1, Detect, [nc, anchors]], # Detect(P3, P4, P5) 51 | ] 52 | -------------------------------------------------------------------------------- /src/models/hub/yolov3-tiny.yaml: -------------------------------------------------------------------------------- 1 | # parameters 2 | nc: 80 # number of classes 3 | depth_multiple: 1.0 # model depth multiple 4 | width_multiple: 1.0 # layer channel multiple 5 | 6 | # anchors 7 | anchors: 8 | - [10,14, 23,27, 37,58] # P4/16 9 | - [81,82, 135,169, 344,319] # P5/32 10 | 11 | # YOLOv3-tiny backbone 12 | backbone: 13 | # [from, number, module, args] 14 | [[-1, 1, Conv, [16, 3, 1]], # 0 15 | [-1, 1, nn.MaxPool2d, [2, 2, 0]], # 1-P1/2 16 | [-1, 1, Conv, [32, 3, 1]], 17 | [-1, 1, nn.MaxPool2d, [2, 2, 0]], # 3-P2/4 18 | [-1, 1, Conv, [64, 3, 1]], 19 | [-1, 1, nn.MaxPool2d, [2, 2, 0]], # 5-P3/8 20 | [-1, 1, Conv, [128, 3, 1]], 21 | [-1, 1, nn.MaxPool2d, [2, 2, 0]], # 7-P4/16 22 | [-1, 1, Conv, [256, 3, 1]], 23 | [-1, 1, nn.MaxPool2d, [2, 2, 0]], # 9-P5/32 24 | [-1, 1, Conv, [512, 3, 1]], 25 | [-1, 1, nn.ZeroPad2d, [[0, 1, 0, 1]]], # 11 26 | [-1, 1, nn.MaxPool2d, [2, 1, 0]], # 12 27 | ] 28 | 29 | # YOLOv3-tiny head 30 | head: 31 | [[-1, 1, Conv, [1024, 3, 1]], 32 | [-1, 1, Conv, [256, 1, 1]], 33 | [-1, 1, Conv, [512, 3, 1]], # 15 (P5/32-large) 34 | 35 | [-2, 1, Conv, [128, 1, 1]], 36 | [-1, 1, nn.Upsample, [None, 2, 'nearest']], 37 | [[-1, 8], 1, Concat, [1]], # cat backbone P4 38 | [-1, 1, Conv, [256, 3, 1]], # 19 (P4/16-medium) 39 | 40 | [[19, 15], 1, Detect, [nc, anchors]], # Detect(P4, P5) 41 | ] 42 | -------------------------------------------------------------------------------- /src/models/hub/yolov3.yaml: -------------------------------------------------------------------------------- 1 | # parameters 2 | nc: 80 # number of classes 3 | depth_multiple: 1.0 # model depth multiple 4 | width_multiple: 1.0 # layer channel multiple 5 | 6 | # anchors 7 | anchors: 8 | - [10,13, 16,30, 33,23] # P3/8 9 | - [30,61, 62,45, 59,119] # P4/16 10 | - [116,90, 156,198, 373,326] # P5/32 11 | 12 | # darknet53 backbone 13 | backbone: 14 | # [from, number, module, args] 15 | [[-1, 1, Conv, [32, 3, 1]], # 0 16 | [-1, 1, Conv, [64, 3, 2]], # 1-P1/2 17 | [-1, 1, Bottleneck, [64]], 18 | [-1, 1, Conv, [128, 3, 2]], # 3-P2/4 19 | [-1, 2, Bottleneck, [128]], 20 | [-1, 1, Conv, [256, 3, 2]], # 5-P3/8 21 | [-1, 8, Bottleneck, [256]], 22 | [-1, 1, Conv, [512, 3, 2]], # 7-P4/16 23 | [-1, 8, Bottleneck, [512]], 24 | [-1, 1, Conv, [1024, 3, 2]], # 9-P5/32 25 | [-1, 4, Bottleneck, [1024]], # 10 26 | ] 27 | 28 | # YOLOv3 head 29 | head: 30 | [[-1, 1, Bottleneck, [1024, False]], 31 | [-1, 1, Conv, [512, [1, 1]]], 32 | [-1, 1, Conv, [1024, 3, 1]], 33 | [-1, 1, Conv, [512, 1, 1]], 34 | [-1, 1, Conv, [1024, 3, 1]], # 15 (P5/32-large) 35 | 36 | [-2, 1, Conv, [256, 1, 1]], 37 | [-1, 1, nn.Upsample, [None, 2, 'nearest']], 38 | [[-1, 8], 1, Concat, [1]], # cat backbone P4 39 | [-1, 1, Bottleneck, [512, False]], 40 | [-1, 1, Bottleneck, [512, False]], 41 | [-1, 1, Conv, [256, 1, 1]], 42 | [-1, 1, Conv, [512, 3, 1]], # 22 (P4/16-medium) 43 | 44 | [-2, 1, Conv, [128, 1, 1]], 45 | [-1, 1, nn.Upsample, [None, 2, 'nearest']], 46 | [[-1, 6], 1, Concat, [1]], # cat backbone P3 47 | [-1, 1, Bottleneck, [256, False]], 48 | [-1, 2, Bottleneck, [256, False]], # 27 (P3/8-small) 49 | 50 | [[27, 22, 15], 1, Detect, [nc, anchors]], # Detect(P3, P4, P5) 51 | ] 52 | -------------------------------------------------------------------------------- /src/models/hub/yolov5-fpn.yaml: -------------------------------------------------------------------------------- 1 | # parameters 2 | nc: 80 # number of classes 3 | depth_multiple: 1.0 # model depth multiple 4 | width_multiple: 1.0 # layer channel multiple 5 | 6 | # anchors 7 | anchors: 8 | - [10,13, 16,30, 33,23] # P3/8 9 | - [30,61, 62,45, 59,119] # P4/16 10 | - [116,90, 156,198, 373,326] # P5/32 11 | 12 | # YOLOv5 backbone 13 | backbone: 14 | # [from, number, module, args] 15 | [[-1, 1, Focus, [64, 3]], # 0-P1/2 16 | [-1, 1, Conv, [128, 3, 2]], # 1-P2/4 17 | [-1, 3, Bottleneck, [128]], 18 | [-1, 1, Conv, [256, 3, 2]], # 3-P3/8 19 | [-1, 9, BottleneckCSP, [256]], 20 | [-1, 1, Conv, [512, 3, 2]], # 5-P4/16 21 | [-1, 9, BottleneckCSP, [512]], 22 | [-1, 1, Conv, [1024, 3, 2]], # 7-P5/32 23 | [-1, 1, SPP, [1024, [5, 9, 13]]], 24 | [-1, 6, BottleneckCSP, [1024]], # 9 25 | ] 26 | 27 | # YOLOv5 FPN head 28 | head: 29 | [[-1, 3, BottleneckCSP, [1024, False]], # 10 (P5/32-large) 30 | 31 | [-1, 1, nn.Upsample, [None, 2, 'nearest']], 32 | [[-1, 6], 1, Concat, [1]], # cat backbone P4 33 | [-1, 1, Conv, [512, 1, 1]], 34 | [-1, 3, BottleneckCSP, [512, False]], # 14 (P4/16-medium) 35 | 36 | [-1, 1, nn.Upsample, [None, 2, 'nearest']], 37 | [[-1, 4], 1, Concat, [1]], # cat backbone P3 38 | [-1, 1, Conv, [256, 1, 1]], 39 | [-1, 3, BottleneckCSP, [256, False]], # 18 (P3/8-small) 40 | 41 | [[18, 14, 10], 1, Detect, [nc, anchors]], # Detect(P3, P4, P5) 42 | ] 43 | -------------------------------------------------------------------------------- /src/models/hub/yolov5-p2.yaml: -------------------------------------------------------------------------------- 1 | # parameters 2 | nc: 80 # number of classes 3 | depth_multiple: 1.0 # model depth multiple 4 | width_multiple: 1.0 # layer channel multiple 5 | 6 | # anchors 7 | anchors: 3 8 | 9 | # YOLOv5 backbone 10 | backbone: 11 | # [from, number, module, args] 12 | [ [ -1, 1, Focus, [ 64, 3 ] ], # 0-P1/2 13 | [ -1, 1, Conv, [ 128, 3, 2 ] ], # 1-P2/4 14 | [ -1, 3, C3, [ 128 ] ], 15 | [ -1, 1, Conv, [ 256, 3, 2 ] ], # 3-P3/8 16 | [ -1, 9, C3, [ 256 ] ], 17 | [ -1, 1, Conv, [ 512, 3, 2 ] ], # 5-P4/16 18 | [ -1, 9, C3, [ 512 ] ], 19 | [ -1, 1, Conv, [ 1024, 3, 2 ] ], # 7-P5/32 20 | [ -1, 1, SPP, [ 1024, [ 5, 9, 13 ] ] ], 21 | [ -1, 3, C3, [ 1024, False ] ], # 9 22 | ] 23 | 24 | # YOLOv5 head 25 | head: 26 | [ [ -1, 1, Conv, [ 512, 1, 1 ] ], 27 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 28 | [ [ -1, 6 ], 1, Concat, [ 1 ] ], # cat backbone P4 29 | [ -1, 3, C3, [ 512, False ] ], # 13 30 | 31 | [ -1, 1, Conv, [ 256, 1, 1 ] ], 32 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 33 | [ [ -1, 4 ], 1, Concat, [ 1 ] ], # cat backbone P3 34 | [ -1, 3, C3, [ 256, False ] ], # 17 (P3/8-small) 35 | 36 | [ -1, 1, Conv, [ 128, 1, 1 ] ], 37 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 38 | [ [ -1, 2 ], 1, Concat, [ 1 ] ], # cat backbone P2 39 | [ -1, 1, C3, [ 128, False ] ], # 21 (P2/4-xsmall) 40 | 41 | [ -1, 1, Conv, [ 128, 3, 2 ] ], 42 | [ [ -1, 18 ], 1, Concat, [ 1 ] ], # cat head P3 43 | [ -1, 3, C3, [ 256, False ] ], # 24 (P3/8-small) 44 | 45 | [ -1, 1, Conv, [ 256, 3, 2 ] ], 46 | [ [ -1, 14 ], 1, Concat, [ 1 ] ], # cat head P4 47 | [ -1, 3, C3, [ 512, False ] ], # 27 (P4/16-medium) 48 | 49 | [ -1, 1, Conv, [ 512, 3, 2 ] ], 50 | [ [ -1, 10 ], 1, Concat, [ 1 ] ], # cat head P5 51 | [ -1, 3, C3, [ 1024, False ] ], # 30 (P5/32-large) 52 | 53 | [ [ 24, 27, 30 ], 1, Detect, [ nc, anchors ] ], # Detect(P3, P4, P5) 54 | ] 55 | -------------------------------------------------------------------------------- /src/models/hub/yolov5-p6.yaml: -------------------------------------------------------------------------------- 1 | # parameters 2 | nc: 80 # number of classes 3 | depth_multiple: 1.0 # model depth multiple 4 | width_multiple: 1.0 # layer channel multiple 5 | 6 | # anchors 7 | anchors: 3 8 | 9 | # YOLOv5 backbone 10 | backbone: 11 | # [from, number, module, args] 12 | [ [ -1, 1, Focus, [ 64, 3 ] ], # 0-P1/2 13 | [ -1, 1, Conv, [ 128, 3, 2 ] ], # 1-P2/4 14 | [ -1, 3, C3, [ 128 ] ], 15 | [ -1, 1, Conv, [ 256, 3, 2 ] ], # 3-P3/8 16 | [ -1, 9, C3, [ 256 ] ], 17 | [ -1, 1, Conv, [ 512, 3, 2 ] ], # 5-P4/16 18 | [ -1, 9, C3, [ 512 ] ], 19 | [ -1, 1, Conv, [ 768, 3, 2 ] ], # 7-P5/32 20 | [ -1, 3, C3, [ 768 ] ], 21 | [ -1, 1, Conv, [ 1024, 3, 2 ] ], # 9-P6/64 22 | [ -1, 1, SPP, [ 1024, [ 3, 5, 7 ] ] ], 23 | [ -1, 3, C3, [ 1024, False ] ], # 11 24 | ] 25 | 26 | # YOLOv5 head 27 | head: 28 | [ [ -1, 1, Conv, [ 768, 1, 1 ] ], 29 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 30 | [ [ -1, 8 ], 1, Concat, [ 1 ] ], # cat backbone P5 31 | [ -1, 3, C3, [ 768, False ] ], # 15 32 | 33 | [ -1, 1, Conv, [ 512, 1, 1 ] ], 34 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 35 | [ [ -1, 6 ], 1, Concat, [ 1 ] ], # cat backbone P4 36 | [ -1, 3, C3, [ 512, False ] ], # 19 37 | 38 | [ -1, 1, Conv, [ 256, 1, 1 ] ], 39 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 40 | [ [ -1, 4 ], 1, Concat, [ 1 ] ], # cat backbone P3 41 | [ -1, 3, C3, [ 256, False ] ], # 23 (P3/8-small) 42 | 43 | [ -1, 1, Conv, [ 256, 3, 2 ] ], 44 | [ [ -1, 20 ], 1, Concat, [ 1 ] ], # cat head P4 45 | [ -1, 3, C3, [ 512, False ] ], # 26 (P4/16-medium) 46 | 47 | [ -1, 1, Conv, [ 512, 3, 2 ] ], 48 | [ [ -1, 16 ], 1, Concat, [ 1 ] ], # cat head P5 49 | [ -1, 3, C3, [ 768, False ] ], # 29 (P5/32-large) 50 | 51 | [ -1, 1, Conv, [ 768, 3, 2 ] ], 52 | [ [ -1, 12 ], 1, Concat, [ 1 ] ], # cat head P6 53 | [ -1, 3, C3, [ 1024, False ] ], # 32 (P5/64-xlarge) 54 | 55 | [ [ 23, 26, 29, 32 ], 1, Detect, [ nc, anchors ] ], # Detect(P3, P4, P5, P6) 56 | ] 57 | -------------------------------------------------------------------------------- /src/models/hub/yolov5-p7.yaml: -------------------------------------------------------------------------------- 1 | # parameters 2 | nc: 80 # number of classes 3 | depth_multiple: 1.0 # model depth multiple 4 | width_multiple: 1.0 # layer channel multiple 5 | 6 | # anchors 7 | anchors: 3 8 | 9 | # YOLOv5 backbone 10 | backbone: 11 | # [from, number, module, args] 12 | [ [ -1, 1, Focus, [ 64, 3 ] ], # 0-P1/2 13 | [ -1, 1, Conv, [ 128, 3, 2 ] ], # 1-P2/4 14 | [ -1, 3, C3, [ 128 ] ], 15 | [ -1, 1, Conv, [ 256, 3, 2 ] ], # 3-P3/8 16 | [ -1, 9, C3, [ 256 ] ], 17 | [ -1, 1, Conv, [ 512, 3, 2 ] ], # 5-P4/16 18 | [ -1, 9, C3, [ 512 ] ], 19 | [ -1, 1, Conv, [ 768, 3, 2 ] ], # 7-P5/32 20 | [ -1, 3, C3, [ 768 ] ], 21 | [ -1, 1, Conv, [ 1024, 3, 2 ] ], # 9-P6/64 22 | [ -1, 3, C3, [ 1024 ] ], 23 | [ -1, 1, Conv, [ 1280, 3, 2 ] ], # 11-P7/128 24 | [ -1, 1, SPP, [ 1280, [ 3, 5 ] ] ], 25 | [ -1, 3, C3, [ 1280, False ] ], # 13 26 | ] 27 | 28 | # YOLOv5 head 29 | head: 30 | [ [ -1, 1, Conv, [ 1024, 1, 1 ] ], 31 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 32 | [ [ -1, 10 ], 1, Concat, [ 1 ] ], # cat backbone P6 33 | [ -1, 3, C3, [ 1024, False ] ], # 17 34 | 35 | [ -1, 1, Conv, [ 768, 1, 1 ] ], 36 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 37 | [ [ -1, 8 ], 1, Concat, [ 1 ] ], # cat backbone P5 38 | [ -1, 3, C3, [ 768, False ] ], # 21 39 | 40 | [ -1, 1, Conv, [ 512, 1, 1 ] ], 41 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 42 | [ [ -1, 6 ], 1, Concat, [ 1 ] ], # cat backbone P4 43 | [ -1, 3, C3, [ 512, False ] ], # 25 44 | 45 | [ -1, 1, Conv, [ 256, 1, 1 ] ], 46 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 47 | [ [ -1, 4 ], 1, Concat, [ 1 ] ], # cat backbone P3 48 | [ -1, 3, C3, [ 256, False ] ], # 29 (P3/8-small) 49 | 50 | [ -1, 1, Conv, [ 256, 3, 2 ] ], 51 | [ [ -1, 26 ], 1, Concat, [ 1 ] ], # cat head P4 52 | [ -1, 3, C3, [ 512, False ] ], # 32 (P4/16-medium) 53 | 54 | [ -1, 1, Conv, [ 512, 3, 2 ] ], 55 | [ [ -1, 22 ], 1, Concat, [ 1 ] ], # cat head P5 56 | [ -1, 3, C3, [ 768, False ] ], # 35 (P5/32-large) 57 | 58 | [ -1, 1, Conv, [ 768, 3, 2 ] ], 59 | [ [ -1, 18 ], 1, Concat, [ 1 ] ], # cat head P6 60 | [ -1, 3, C3, [ 1024, False ] ], # 38 (P6/64-xlarge) 61 | 62 | [ -1, 1, Conv, [ 1024, 3, 2 ] ], 63 | [ [ -1, 14 ], 1, Concat, [ 1 ] ], # cat head P7 64 | [ -1, 3, C3, [ 1280, False ] ], # 41 (P7/128-xxlarge) 65 | 66 | [ [ 29, 32, 35, 38, 41 ], 1, Detect, [ nc, anchors ] ], # Detect(P3, P4, P5, P6, P7) 67 | ] 68 | -------------------------------------------------------------------------------- /src/models/hub/yolov5-panet.yaml: -------------------------------------------------------------------------------- 1 | # parameters 2 | nc: 80 # number of classes 3 | depth_multiple: 1.0 # model depth multiple 4 | width_multiple: 1.0 # layer channel multiple 5 | 6 | # anchors 7 | anchors: 8 | - [10,13, 16,30, 33,23] # P3/8 9 | - [30,61, 62,45, 59,119] # P4/16 10 | - [116,90, 156,198, 373,326] # P5/32 11 | 12 | # YOLOv5 backbone 13 | backbone: 14 | # [from, number, module, args] 15 | [[-1, 1, Focus, [64, 3]], # 0-P1/2 16 | [-1, 1, Conv, [128, 3, 2]], # 1-P2/4 17 | [-1, 3, BottleneckCSP, [128]], 18 | [-1, 1, Conv, [256, 3, 2]], # 3-P3/8 19 | [-1, 9, BottleneckCSP, [256]], 20 | [-1, 1, Conv, [512, 3, 2]], # 5-P4/16 21 | [-1, 9, BottleneckCSP, [512]], 22 | [-1, 1, Conv, [1024, 3, 2]], # 7-P5/32 23 | [-1, 1, SPP, [1024, [5, 9, 13]]], 24 | [-1, 3, BottleneckCSP, [1024, False]], # 9 25 | ] 26 | 27 | # YOLOv5 PANet head 28 | head: 29 | [[-1, 1, Conv, [512, 1, 1]], 30 | [-1, 1, nn.Upsample, [None, 2, 'nearest']], 31 | [[-1, 6], 1, Concat, [1]], # cat backbone P4 32 | [-1, 3, BottleneckCSP, [512, False]], # 13 33 | 34 | [-1, 1, Conv, [256, 1, 1]], 35 | [-1, 1, nn.Upsample, [None, 2, 'nearest']], 36 | [[-1, 4], 1, Concat, [1]], # cat backbone P3 37 | [-1, 3, BottleneckCSP, [256, False]], # 17 (P3/8-small) 38 | 39 | [-1, 1, Conv, [256, 3, 2]], 40 | [[-1, 14], 1, Concat, [1]], # cat head P4 41 | [-1, 3, BottleneckCSP, [512, False]], # 20 (P4/16-medium) 42 | 43 | [-1, 1, Conv, [512, 3, 2]], 44 | [[-1, 10], 1, Concat, [1]], # cat head P5 45 | [-1, 3, BottleneckCSP, [1024, False]], # 23 (P5/32-large) 46 | 47 | [[17, 20, 23], 1, Detect, [nc, anchors]], # Detect(P3, P4, P5) 48 | ] 49 | -------------------------------------------------------------------------------- /src/models/hub/yolov5l6.yaml: -------------------------------------------------------------------------------- 1 | # parameters 2 | nc: 80 # number of classes 3 | depth_multiple: 1.0 # model depth multiple 4 | width_multiple: 1.0 # layer channel multiple 5 | 6 | # anchors 7 | anchors: 8 | - [ 19,27, 44,40, 38,94 ] # P3/8 9 | - [ 96,68, 86,152, 180,137 ] # P4/16 10 | - [ 140,301, 303,264, 238,542 ] # P5/32 11 | - [ 436,615, 739,380, 925,792 ] # P6/64 12 | 13 | # YOLOv5 backbone 14 | backbone: 15 | # [from, number, module, args] 16 | [ [ -1, 1, Focus, [ 64, 3 ] ], # 0-P1/2 17 | [ -1, 1, Conv, [ 128, 3, 2 ] ], # 1-P2/4 18 | [ -1, 3, C3, [ 128 ] ], 19 | [ -1, 1, Conv, [ 256, 3, 2 ] ], # 3-P3/8 20 | [ -1, 9, C3, [ 256 ] ], 21 | [ -1, 1, Conv, [ 512, 3, 2 ] ], # 5-P4/16 22 | [ -1, 9, C3, [ 512 ] ], 23 | [ -1, 1, Conv, [ 768, 3, 2 ] ], # 7-P5/32 24 | [ -1, 3, C3, [ 768 ] ], 25 | [ -1, 1, Conv, [ 1024, 3, 2 ] ], # 9-P6/64 26 | [ -1, 1, SPP, [ 1024, [ 3, 5, 7 ] ] ], 27 | [ -1, 3, C3, [ 1024, False ] ], # 11 28 | ] 29 | 30 | # YOLOv5 head 31 | head: 32 | [ [ -1, 1, Conv, [ 768, 1, 1 ] ], 33 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 34 | [ [ -1, 8 ], 1, Concat, [ 1 ] ], # cat backbone P5 35 | [ -1, 3, C3, [ 768, False ] ], # 15 36 | 37 | [ -1, 1, Conv, [ 512, 1, 1 ] ], 38 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 39 | [ [ -1, 6 ], 1, Concat, [ 1 ] ], # cat backbone P4 40 | [ -1, 3, C3, [ 512, False ] ], # 19 41 | 42 | [ -1, 1, Conv, [ 256, 1, 1 ] ], 43 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 44 | [ [ -1, 4 ], 1, Concat, [ 1 ] ], # cat backbone P3 45 | [ -1, 3, C3, [ 256, False ] ], # 23 (P3/8-small) 46 | 47 | [ -1, 1, Conv, [ 256, 3, 2 ] ], 48 | [ [ -1, 20 ], 1, Concat, [ 1 ] ], # cat head P4 49 | [ -1, 3, C3, [ 512, False ] ], # 26 (P4/16-medium) 50 | 51 | [ -1, 1, Conv, [ 512, 3, 2 ] ], 52 | [ [ -1, 16 ], 1, Concat, [ 1 ] ], # cat head P5 53 | [ -1, 3, C3, [ 768, False ] ], # 29 (P5/32-large) 54 | 55 | [ -1, 1, Conv, [ 768, 3, 2 ] ], 56 | [ [ -1, 12 ], 1, Concat, [ 1 ] ], # cat head P6 57 | [ -1, 3, C3, [ 1024, False ] ], # 32 (P6/64-xlarge) 58 | 59 | [ [ 23, 26, 29, 32 ], 1, Detect, [ nc, anchors ] ], # Detect(P3, P4, P5, P6) 60 | ] 61 | -------------------------------------------------------------------------------- /src/models/hub/yolov5m6.yaml: -------------------------------------------------------------------------------- 1 | # parameters 2 | nc: 80 # number of classes 3 | depth_multiple: 0.67 # model depth multiple 4 | width_multiple: 0.75 # layer channel multiple 5 | 6 | # anchors 7 | anchors: 8 | - [ 19,27, 44,40, 38,94 ] # P3/8 9 | - [ 96,68, 86,152, 180,137 ] # P4/16 10 | - [ 140,301, 303,264, 238,542 ] # P5/32 11 | - [ 436,615, 739,380, 925,792 ] # P6/64 12 | 13 | # YOLOv5 backbone 14 | backbone: 15 | # [from, number, module, args] 16 | [ [ -1, 1, Focus, [ 64, 3 ] ], # 0-P1/2 17 | [ -1, 1, Conv, [ 128, 3, 2 ] ], # 1-P2/4 18 | [ -1, 3, C3, [ 128 ] ], 19 | [ -1, 1, Conv, [ 256, 3, 2 ] ], # 3-P3/8 20 | [ -1, 9, C3, [ 256 ] ], 21 | [ -1, 1, Conv, [ 512, 3, 2 ] ], # 5-P4/16 22 | [ -1, 9, C3, [ 512 ] ], 23 | [ -1, 1, Conv, [ 768, 3, 2 ] ], # 7-P5/32 24 | [ -1, 3, C3, [ 768 ] ], 25 | [ -1, 1, Conv, [ 1024, 3, 2 ] ], # 9-P6/64 26 | [ -1, 1, SPP, [ 1024, [ 3, 5, 7 ] ] ], 27 | [ -1, 3, C3, [ 1024, False ] ], # 11 28 | ] 29 | 30 | # YOLOv5 head 31 | head: 32 | [ [ -1, 1, Conv, [ 768, 1, 1 ] ], 33 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 34 | [ [ -1, 8 ], 1, Concat, [ 1 ] ], # cat backbone P5 35 | [ -1, 3, C3, [ 768, False ] ], # 15 36 | 37 | [ -1, 1, Conv, [ 512, 1, 1 ] ], 38 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 39 | [ [ -1, 6 ], 1, Concat, [ 1 ] ], # cat backbone P4 40 | [ -1, 3, C3, [ 512, False ] ], # 19 41 | 42 | [ -1, 1, Conv, [ 256, 1, 1 ] ], 43 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 44 | [ [ -1, 4 ], 1, Concat, [ 1 ] ], # cat backbone P3 45 | [ -1, 3, C3, [ 256, False ] ], # 23 (P3/8-small) 46 | 47 | [ -1, 1, Conv, [ 256, 3, 2 ] ], 48 | [ [ -1, 20 ], 1, Concat, [ 1 ] ], # cat head P4 49 | [ -1, 3, C3, [ 512, False ] ], # 26 (P4/16-medium) 50 | 51 | [ -1, 1, Conv, [ 512, 3, 2 ] ], 52 | [ [ -1, 16 ], 1, Concat, [ 1 ] ], # cat head P5 53 | [ -1, 3, C3, [ 768, False ] ], # 29 (P5/32-large) 54 | 55 | [ -1, 1, Conv, [ 768, 3, 2 ] ], 56 | [ [ -1, 12 ], 1, Concat, [ 1 ] ], # cat head P6 57 | [ -1, 3, C3, [ 1024, False ] ], # 32 (P6/64-xlarge) 58 | 59 | [ [ 23, 26, 29, 32 ], 1, Detect, [ nc, anchors ] ], # Detect(P3, P4, P5, P6) 60 | ] 61 | -------------------------------------------------------------------------------- /src/models/hub/yolov5s6.yaml: -------------------------------------------------------------------------------- 1 | # parameters 2 | nc: 80 # number of classes 3 | depth_multiple: 0.33 # model depth multiple 4 | width_multiple: 0.50 # layer channel multiple 5 | 6 | # anchors 7 | anchors: 8 | - [ 19,27, 44,40, 38,94 ] # P3/8 9 | - [ 96,68, 86,152, 180,137 ] # P4/16 10 | - [ 140,301, 303,264, 238,542 ] # P5/32 11 | - [ 436,615, 739,380, 925,792 ] # P6/64 12 | 13 | # YOLOv5 backbone 14 | backbone: 15 | # [from, number, module, args] 16 | [ [ -1, 1, Focus, [ 64, 3 ] ], # 0-P1/2 17 | [ -1, 1, Conv, [ 128, 3, 2 ] ], # 1-P2/4 18 | [ -1, 3, C3, [ 128 ] ], 19 | [ -1, 1, Conv, [ 256, 3, 2 ] ], # 3-P3/8 20 | [ -1, 9, C3, [ 256 ] ], 21 | [ -1, 1, Conv, [ 512, 3, 2 ] ], # 5-P4/16 22 | [ -1, 9, C3, [ 512 ] ], 23 | [ -1, 1, Conv, [ 768, 3, 2 ] ], # 7-P5/32 24 | [ -1, 3, C3, [ 768 ] ], 25 | [ -1, 1, Conv, [ 1024, 3, 2 ] ], # 9-P6/64 26 | [ -1, 1, SPP, [ 1024, [ 3, 5, 7 ] ] ], 27 | [ -1, 3, C3, [ 1024, False ] ], # 11 28 | ] 29 | 30 | # YOLOv5 head 31 | head: 32 | [ [ -1, 1, Conv, [ 768, 1, 1 ] ], 33 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 34 | [ [ -1, 8 ], 1, Concat, [ 1 ] ], # cat backbone P5 35 | [ -1, 3, C3, [ 768, False ] ], # 15 36 | 37 | [ -1, 1, Conv, [ 512, 1, 1 ] ], 38 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 39 | [ [ -1, 6 ], 1, Concat, [ 1 ] ], # cat backbone P4 40 | [ -1, 3, C3, [ 512, False ] ], # 19 41 | 42 | [ -1, 1, Conv, [ 256, 1, 1 ] ], 43 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 44 | [ [ -1, 4 ], 1, Concat, [ 1 ] ], # cat backbone P3 45 | [ -1, 3, C3, [ 256, False ] ], # 23 (P3/8-small) 46 | 47 | [ -1, 1, Conv, [ 256, 3, 2 ] ], 48 | [ [ -1, 20 ], 1, Concat, [ 1 ] ], # cat head P4 49 | [ -1, 3, C3, [ 512, False ] ], # 26 (P4/16-medium) 50 | 51 | [ -1, 1, Conv, [ 512, 3, 2 ] ], 52 | [ [ -1, 16 ], 1, Concat, [ 1 ] ], # cat head P5 53 | [ -1, 3, C3, [ 768, False ] ], # 29 (P5/32-large) 54 | 55 | [ -1, 1, Conv, [ 768, 3, 2 ] ], 56 | [ [ -1, 12 ], 1, Concat, [ 1 ] ], # cat head P6 57 | [ -1, 3, C3, [ 1024, False ] ], # 32 (P6/64-xlarge) 58 | 59 | [ [ 23, 26, 29, 32 ], 1, Detect, [ nc, anchors ] ], # Detect(P3, P4, P5, P6) 60 | ] 61 | -------------------------------------------------------------------------------- /src/models/hub/yolov5x6.yaml: -------------------------------------------------------------------------------- 1 | # parameters 2 | nc: 80 # number of classes 3 | depth_multiple: 1.33 # model depth multiple 4 | width_multiple: 1.25 # layer channel multiple 5 | 6 | # anchors 7 | anchors: 8 | - [ 19,27, 44,40, 38,94 ] # P3/8 9 | - [ 96,68, 86,152, 180,137 ] # P4/16 10 | - [ 140,301, 303,264, 238,542 ] # P5/32 11 | - [ 436,615, 739,380, 925,792 ] # P6/64 12 | 13 | # YOLOv5 backbone 14 | backbone: 15 | # [from, number, module, args] 16 | [ [ -1, 1, Focus, [ 64, 3 ] ], # 0-P1/2 17 | [ -1, 1, Conv, [ 128, 3, 2 ] ], # 1-P2/4 18 | [ -1, 3, C3, [ 128 ] ], 19 | [ -1, 1, Conv, [ 256, 3, 2 ] ], # 3-P3/8 20 | [ -1, 9, C3, [ 256 ] ], 21 | [ -1, 1, Conv, [ 512, 3, 2 ] ], # 5-P4/16 22 | [ -1, 9, C3, [ 512 ] ], 23 | [ -1, 1, Conv, [ 768, 3, 2 ] ], # 7-P5/32 24 | [ -1, 3, C3, [ 768 ] ], 25 | [ -1, 1, Conv, [ 1024, 3, 2 ] ], # 9-P6/64 26 | [ -1, 1, SPP, [ 1024, [ 3, 5, 7 ] ] ], 27 | [ -1, 3, C3, [ 1024, False ] ], # 11 28 | ] 29 | 30 | # YOLOv5 head 31 | head: 32 | [ [ -1, 1, Conv, [ 768, 1, 1 ] ], 33 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 34 | [ [ -1, 8 ], 1, Concat, [ 1 ] ], # cat backbone P5 35 | [ -1, 3, C3, [ 768, False ] ], # 15 36 | 37 | [ -1, 1, Conv, [ 512, 1, 1 ] ], 38 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 39 | [ [ -1, 6 ], 1, Concat, [ 1 ] ], # cat backbone P4 40 | [ -1, 3, C3, [ 512, False ] ], # 19 41 | 42 | [ -1, 1, Conv, [ 256, 1, 1 ] ], 43 | [ -1, 1, nn.Upsample, [ None, 2, 'nearest' ] ], 44 | [ [ -1, 4 ], 1, Concat, [ 1 ] ], # cat backbone P3 45 | [ -1, 3, C3, [ 256, False ] ], # 23 (P3/8-small) 46 | 47 | [ -1, 1, Conv, [ 256, 3, 2 ] ], 48 | [ [ -1, 20 ], 1, Concat, [ 1 ] ], # cat head P4 49 | [ -1, 3, C3, [ 512, False ] ], # 26 (P4/16-medium) 50 | 51 | [ -1, 1, Conv, [ 512, 3, 2 ] ], 52 | [ [ -1, 16 ], 1, Concat, [ 1 ] ], # cat head P5 53 | [ -1, 3, C3, [ 768, False ] ], # 29 (P5/32-large) 54 | 55 | [ -1, 1, Conv, [ 768, 3, 2 ] ], 56 | [ [ -1, 12 ], 1, Concat, [ 1 ] ], # cat head P6 57 | [ -1, 3, C3, [ 1024, False ] ], # 32 (P6/64-xlarge) 58 | 59 | [ [ 23, 26, 29, 32 ], 1, Detect, [ nc, anchors ] ], # Detect(P3, P4, P5, P6) 60 | ] 61 | -------------------------------------------------------------------------------- /src/models/yolo.py: -------------------------------------------------------------------------------- 1 | import argparse 2 | import logging 3 | import sys 4 | from copy import deepcopy 5 | from pathlib import Path 6 | 7 | sys.path.append('./') # to run '$ python *.py' files in subdirectories 8 | logger = logging.getLogger(__name__) 9 | 10 | from models.common import * 11 | from models.experimental import * 12 | from utils.autoanchor import check_anchor_order 13 | from utils.general import make_divisible, check_file, set_logging 14 | from utils.torch_utils import time_synchronized, fuse_conv_and_bn, model_info, scale_img, initialize_weights, \ 15 | select_device, copy_attr 16 | 17 | try: 18 | import thop # for FLOPS computation 19 | except ImportError: 20 | thop = None 21 | 22 | 23 | class Detect(nn.Module): 24 | stride = None # strides computed during build 25 | export = False # onnx export 26 | 27 | def __init__(self, nc=80, anchors=(), ch=()): # detection layer 28 | super(Detect, self).__init__() 29 | self.nc = nc # number of classes 30 | self.no = nc + 5 # number of outputs per anchor 31 | self.nl = len(anchors) # number of detection layers 32 | self.na = len(anchors[0]) // 2 # number of anchors 33 | self.grid = [torch.zeros(1)] * self.nl # init grid 34 | a = torch.tensor(anchors).float().view(self.nl, -1, 2) 35 | self.register_buffer('anchors', a) # shape(nl,na,2) 36 | self.register_buffer('anchor_grid', a.clone().view(self.nl, 1, -1, 1, 1, 2)) # shape(nl,1,na,1,1,2) 37 | self.m = nn.ModuleList(nn.Conv2d(x, self.no * self.na, 1) for x in ch) # output conv 38 | 39 | def forward(self, x): 40 | # x = x.copy() # for profiling 41 | z = [] # inference output 42 | self.training |= self.export 43 | for i in range(self.nl): 44 | x[i] = self.m[i](x[i]) # conv 45 | bs, _, ny, nx = x[i].shape # x(bs,255,20,20) to x(bs,3,20,20,85) 46 | x[i] = x[i].view(bs, self.na, self.no, ny, nx).permute(0, 1, 3, 4, 2).contiguous() 47 | 48 | if not self.training: # inference 49 | if self.grid[i].shape[2:4] != x[i].shape[2:4]: 50 | self.grid[i] = self._make_grid(nx, ny).to(x[i].device) 51 | 52 | y = x[i].sigmoid() 53 | y[..., 0:2] = (y[..., 0:2] * 2. - 0.5 + self.grid[i].to(x[i].device)) * self.stride[i] # xy 54 | y[..., 2:4] = (y[..., 2:4] * 2) ** 2 * self.anchor_grid[i] # wh 55 | z.append(y.view(bs, -1, self.no)) 56 | 57 | return x if self.training else (torch.cat(z, 1), x) 58 | 59 | @staticmethod 60 | def _make_grid(nx=20, ny=20): 61 | yv, xv = torch.meshgrid([torch.arange(ny), torch.arange(nx)]) 62 | return torch.stack((xv, yv), 2).view((1, 1, ny, nx, 2)).float() 63 | 64 | 65 | class Model(nn.Module): 66 | def __init__(self, cfg='yolov5s.yaml', ch=3, nc=None): # model, input channels, number of classes 67 | super(Model, self).__init__() 68 | if isinstance(cfg, dict): 69 | self.yaml = cfg # model dict 70 | else: # is *.yaml 71 | import yaml # for torch hub 72 | self.yaml_file = Path(cfg).name 73 | with open(cfg) as f: 74 | self.yaml = yaml.load(f, Loader=yaml.SafeLoader) # model dict 75 | 76 | # Define model 77 | ch = self.yaml['ch'] = self.yaml.get('ch', ch) # input channels 78 | if nc and nc != self.yaml['nc']: 79 | logger.info('Overriding model.yaml nc=%g with nc=%g' % (self.yaml['nc'], nc)) 80 | self.yaml['nc'] = nc # override yaml value 81 | self.model, self.save = parse_model(deepcopy(self.yaml), ch=[ch]) # model, savelist 82 | self.names = [str(i) for i in range(self.yaml['nc'])] # default names 83 | # print([x.shape for x in self.forward(torch.zeros(1, ch, 64, 64))]) 84 | 85 | # Build strides, anchors 86 | m = self.model[-1] # Detect() 87 | if isinstance(m, Detect): 88 | s = 256 # 2x min stride 89 | m.stride = torch.tensor([s / x.shape[-2] for x in self.forward(torch.zeros(1, ch, s, s))]) # forward 90 | m.anchors /= m.stride.view(-1, 1, 1) 91 | check_anchor_order(m) 92 | self.stride = m.stride 93 | self._initialize_biases() # only run once 94 | # print('Strides: %s' % m.stride.tolist()) 95 | 96 | # Init weights, biases 97 | initialize_weights(self) 98 | self.info() 99 | logger.info('') 100 | 101 | def forward(self, x, augment=False, profile=False): 102 | if augment: 103 | img_size = x.shape[-2:] # height, width 104 | s = [1, 0.83, 0.67] # scales 105 | f = [None, 3, None] # flips (2-ud, 3-lr) 106 | y = [] # outputs 107 | for si, fi in zip(s, f): 108 | xi = scale_img(x.flip(fi) if fi else x, si, gs=int(self.stride.max())) 109 | yi = self.forward_once(xi)[0] # forward 110 | # cv2.imwrite(f'img_{si}.jpg', 255 * xi[0].cpu().numpy().transpose((1, 2, 0))[:, :, ::-1]) # save 111 | yi[..., :4] /= si # de-scale 112 | if fi == 2: 113 | yi[..., 1] = img_size[0] - yi[..., 1] # de-flip ud 114 | elif fi == 3: 115 | yi[..., 0] = img_size[1] - yi[..., 0] # de-flip lr 116 | y.append(yi) 117 | return torch.cat(y, 1), None # augmented inference, train 118 | else: 119 | return self.forward_once(x, profile) # single-scale inference, train 120 | 121 | def forward_once(self, x, profile=False): 122 | y, dt = [], [] # outputs 123 | for m in self.model: 124 | if m.f != -1: # if not from previous layer 125 | x = y[m.f] if isinstance(m.f, int) else [x if j == -1 else y[j] for j in m.f] # from earlier layers 126 | 127 | if profile: 128 | o = thop.profile(m, inputs=(x,), verbose=False)[0] / 1E9 * 2 if thop else 0 # FLOPS 129 | t = time_synchronized() 130 | for _ in range(10): 131 | _ = m(x) 132 | dt.append((time_synchronized() - t) * 100) 133 | print('%10.1f%10.0f%10.1fms %-40s' % (o, m.np, dt[-1], m.type)) 134 | 135 | x = m(x) # run 136 | y.append(x if m.i in self.save else None) # save output 137 | 138 | if profile: 139 | print('%.1fms total' % sum(dt)) 140 | return x 141 | 142 | def _initialize_biases(self, cf=None): # initialize biases into Detect(), cf is class frequency 143 | # https://arxiv.org/abs/1708.02002 section 3.3 144 | # cf = torch.bincount(torch.tensor(np.concatenate(dataset.labels, 0)[:, 0]).long(), minlength=nc) + 1. 145 | m = self.model[-1] # Detect() module 146 | for mi, s in zip(m.m, m.stride): # from 147 | b = mi.bias.view(m.na, -1) # conv.bias(255) to (3,85) 148 | b.data[:, 4] += math.log(8 / (640 / s) ** 2) # obj (8 objects per 640 image) 149 | b.data[:, 5:] += math.log(0.6 / (m.nc - 0.99)) if cf is None else torch.log(cf / cf.sum()) # cls 150 | mi.bias = torch.nn.Parameter(b.view(-1), requires_grad=True) 151 | 152 | def _print_biases(self): 153 | m = self.model[-1] # Detect() module 154 | for mi in m.m: # from 155 | b = mi.bias.detach().view(m.na, -1).T # conv.bias(255) to (3,85) 156 | print(('%6g Conv2d.bias:' + '%10.3g' * 6) % (mi.weight.shape[1], *b[:5].mean(1).tolist(), b[5:].mean())) 157 | 158 | # def _print_weights(self): 159 | # for m in self.model.modules(): 160 | # if type(m) is Bottleneck: 161 | # print('%10.3g' % (m.w.detach().sigmoid() * 2)) # shortcut weights 162 | 163 | def fuse(self): # fuse model Conv2d() + BatchNorm2d() layers 164 | print('Fusing layers... ') 165 | for m in self.model.modules(): 166 | if type(m) is Conv and hasattr(m, 'bn'): 167 | m.conv = fuse_conv_and_bn(m.conv, m.bn) # update conv 168 | delattr(m, 'bn') # remove batchnorm 169 | m.forward = m.fuseforward # update forward 170 | self.info() 171 | return self 172 | 173 | def nms(self, mode=True): # add or remove NMS module 174 | present = type(self.model[-1]) is NMS # last layer is NMS 175 | if mode and not present: 176 | print('Adding NMS... ') 177 | m = NMS() # module 178 | m.f = -1 # from 179 | m.i = self.model[-1].i + 1 # index 180 | self.model.add_module(name='%s' % m.i, module=m) # add 181 | self.eval() 182 | elif not mode and present: 183 | print('Removing NMS... ') 184 | self.model = self.model[:-1] # remove 185 | return self 186 | 187 | def autoshape(self): # add autoShape module 188 | print('Adding autoShape... ') 189 | m = autoShape(self) # wrap model 190 | copy_attr(m, self, include=('yaml', 'nc', 'hyp', 'names', 'stride'), exclude=()) # copy attributes 191 | return m 192 | 193 | def info(self, verbose=False, img_size=640): # print model information 194 | model_info(self, verbose, img_size) 195 | 196 | 197 | def parse_model(d, ch): # model_dict, input_channels(3) 198 | logger.info('\n%3s%18s%3s%10s %-40s%-30s' % ('', 'from', 'n', 'params', 'module', 'arguments')) 199 | anchors, nc, gd, gw = d['anchors'], d['nc'], d['depth_multiple'], d['width_multiple'] 200 | na = (len(anchors[0]) // 2) if isinstance(anchors, list) else anchors # number of anchors 201 | no = na * (nc + 5) # number of outputs = anchors * (classes + 5) 202 | 203 | layers, save, c2 = [], [], ch[-1] # layers, savelist, ch out 204 | for i, (f, n, m, args) in enumerate(d['backbone'] + d['head']): # from, number, module, args 205 | m = eval(m) if isinstance(m, str) else m # eval strings 206 | for j, a in enumerate(args): 207 | try: 208 | args[j] = eval(a) if isinstance(a, str) else a # eval strings 209 | except: 210 | pass 211 | 212 | n = max(round(n * gd), 1) if n > 1 else n # depth gain 213 | if m in [Conv, GhostConv, Bottleneck, GhostBottleneck, SPP, DWConv, MixConv2d, Focus, CrossConv, BottleneckCSP, 214 | C3]: 215 | c1, c2 = ch[f], args[0] 216 | 217 | # Normal 218 | # if i > 0 and args[0] != no: # channel expansion factor 219 | # ex = 1.75 # exponential (default 2.0) 220 | # e = math.log(c2 / ch[1]) / math.log(2) 221 | # c2 = int(ch[1] * ex ** e) 222 | # if m != Focus: 223 | 224 | c2 = make_divisible(c2 * gw, 8) if c2 != no else c2 225 | 226 | # Experimental 227 | # if i > 0 and args[0] != no: # channel expansion factor 228 | # ex = 1 + gw # exponential (default 2.0) 229 | # ch1 = 32 # ch[1] 230 | # e = math.log(c2 / ch1) / math.log(2) # level 1-n 231 | # c2 = int(ch1 * ex ** e) 232 | # if m != Focus: 233 | # c2 = make_divisible(c2, 8) if c2 != no else c2 234 | 235 | args = [c1, c2, *args[1:]] 236 | if m in [BottleneckCSP, C3]: 237 | args.insert(2, n) 238 | n = 1 239 | elif m is nn.BatchNorm2d: 240 | args = [ch[f]] 241 | elif m is Concat: 242 | c2 = sum([ch[x if x < 0 else x + 1] for x in f]) 243 | elif m is Detect: 244 | args.append([ch[x + 1] for x in f]) 245 | if isinstance(args[1], int): # number of anchors 246 | args[1] = [list(range(args[1] * 2))] * len(f) 247 | elif m is Contract: 248 | c2 = ch[f if f < 0 else f + 1] * args[0] ** 2 249 | elif m is Expand: 250 | c2 = ch[f if f < 0 else f + 1] // args[0] ** 2 251 | else: 252 | c2 = ch[f if f < 0 else f + 1] 253 | 254 | m_ = nn.Sequential(*[m(*args) for _ in range(n)]) if n > 1 else m(*args) # module 255 | t = str(m)[8:-2].replace('__main__.', '') # module type 256 | np = sum([x.numel() for x in m_.parameters()]) # number params 257 | m_.i, m_.f, m_.type, m_.np = i, f, t, np # attach index, 'from' index, type, number params 258 | logger.info('%3s%18s%3s%10.0f %-40s%-30s' % (i, f, n, np, t, args)) # print 259 | save.extend(x % i for x in ([f] if isinstance(f, int) else f) if x != -1) # append to savelist 260 | layers.append(m_) 261 | ch.append(c2) 262 | return nn.Sequential(*layers), sorted(save) 263 | 264 | 265 | if __name__ == '__main__': 266 | parser = argparse.ArgumentParser() 267 | parser.add_argument('--cfg', type=str, default='yolov5s.yaml', help='model.yaml') 268 | parser.add_argument('--device', default='', help='cuda device, i.e. 0 or 0,1,2,3 or cpu') 269 | opt = parser.parse_args() 270 | opt.cfg = check_file(opt.cfg) # check file 271 | set_logging() 272 | device = select_device(opt.device) 273 | 274 | # Create model 275 | model = Model(opt.cfg).to(device) 276 | model.train() 277 | 278 | # Profile 279 | # img = torch.rand(8 if torch.cuda.is_available() else 1, 3, 640, 640).to(device) 280 | # y = model(img, profile=True) 281 | 282 | # Tensorboard 283 | # from torch.utils.tensorboard import SummaryWriter 284 | # tb_writer = SummaryWriter() 285 | # print("Run 'tensorboard --logdir=models/runs' to view tensorboard at http://localhost:6006/") 286 | # tb_writer.add_graph(model.model, img) # add model to tensorboard 287 | # tb_writer.add_image('test', img[0], dataformats='CWH') # add model to tensorboard 288 | -------------------------------------------------------------------------------- /src/models/yolov5l.yaml: -------------------------------------------------------------------------------- 1 | # parameters 2 | nc: 80 # number of classes 3 | depth_multiple: 1.0 # model depth multiple 4 | width_multiple: 1.0 # layer channel multiple 5 | 6 | # anchors 7 | anchors: 8 | - [10,13, 16,30, 33,23] # P3/8 9 | - [30,61, 62,45, 59,119] # P4/16 10 | - [116,90, 156,198, 373,326] # P5/32 11 | 12 | # YOLOv5 backbone 13 | backbone: 14 | # [from, number, module, args] 15 | [[-1, 1, Focus, [64, 3]], # 0-P1/2 16 | [-1, 1, Conv, [128, 3, 2]], # 1-P2/4 17 | [-1, 3, C3, [128]], 18 | [-1, 1, Conv, [256, 3, 2]], # 3-P3/8 19 | [-1, 9, C3, [256]], 20 | [-1, 1, Conv, [512, 3, 2]], # 5-P4/16 21 | [-1, 9, C3, [512]], 22 | [-1, 1, Conv, [1024, 3, 2]], # 7-P5/32 23 | [-1, 1, SPP, [1024, [5, 9, 13]]], 24 | [-1, 3, C3, [1024, False]], # 9 25 | ] 26 | 27 | # YOLOv5 head 28 | head: 29 | [[-1, 1, Conv, [512, 1, 1]], 30 | [-1, 1, nn.Upsample, [None, 2, 'nearest']], 31 | [[-1, 6], 1, Concat, [1]], # cat backbone P4 32 | [-1, 3, C3, [512, False]], # 13 33 | 34 | [-1, 1, Conv, [256, 1, 1]], 35 | [-1, 1, nn.Upsample, [None, 2, 'nearest']], 36 | [[-1, 4], 1, Concat, [1]], # cat backbone P3 37 | [-1, 3, C3, [256, False]], # 17 (P3/8-small) 38 | 39 | [-1, 1, Conv, [256, 3, 2]], 40 | [[-1, 14], 1, Concat, [1]], # cat head P4 41 | [-1, 3, C3, [512, False]], # 20 (P4/16-medium) 42 | 43 | [-1, 1, Conv, [512, 3, 2]], 44 | [[-1, 10], 1, Concat, [1]], # cat head P5 45 | [-1, 3, C3, [1024, False]], # 23 (P5/32-large) 46 | 47 | [[17, 20, 23], 1, Detect, [nc, anchors]], # Detect(P3, P4, P5) 48 | ] 49 | -------------------------------------------------------------------------------- /src/models/yolov5m.yaml: -------------------------------------------------------------------------------- 1 | # parameters 2 | nc: 80 # number of classes 3 | depth_multiple: 0.67 # model depth multiple 4 | width_multiple: 0.75 # layer channel multiple 5 | 6 | # anchors 7 | anchors: 8 | - [10,13, 16,30, 33,23] # P3/8 9 | - [30,61, 62,45, 59,119] # P4/16 10 | - [116,90, 156,198, 373,326] # P5/32 11 | 12 | # YOLOv5 backbone 13 | backbone: 14 | # [from, number, module, args] 15 | [[-1, 1, Focus, [64, 3]], # 0-P1/2 16 | [-1, 1, Conv, [128, 3, 2]], # 1-P2/4 17 | [-1, 3, C3, [128]], 18 | [-1, 1, Conv, [256, 3, 2]], # 3-P3/8 19 | [-1, 9, C3, [256]], 20 | [-1, 1, Conv, [512, 3, 2]], # 5-P4/16 21 | [-1, 9, C3, [512]], 22 | [-1, 1, Conv, [1024, 3, 2]], # 7-P5/32 23 | [-1, 1, SPP, [1024, [5, 9, 13]]], 24 | [-1, 3, C3, [1024, False]], # 9 25 | ] 26 | 27 | # YOLOv5 head 28 | head: 29 | [[-1, 1, Conv, [512, 1, 1]], 30 | [-1, 1, nn.Upsample, [None, 2, 'nearest']], 31 | [[-1, 6], 1, Concat, [1]], # cat backbone P4 32 | [-1, 3, C3, [512, False]], # 13 33 | 34 | [-1, 1, Conv, [256, 1, 1]], 35 | [-1, 1, nn.Upsample, [None, 2, 'nearest']], 36 | [[-1, 4], 1, Concat, [1]], # cat backbone P3 37 | [-1, 3, C3, [256, False]], # 17 (P3/8-small) 38 | 39 | [-1, 1, Conv, [256, 3, 2]], 40 | [[-1, 14], 1, Concat, [1]], # cat head P4 41 | [-1, 3, C3, [512, False]], # 20 (P4/16-medium) 42 | 43 | [-1, 1, Conv, [512, 3, 2]], 44 | [[-1, 10], 1, Concat, [1]], # cat head P5 45 | [-1, 3, C3, [1024, False]], # 23 (P5/32-large) 46 | 47 | [[17, 20, 23], 1, Detect, [nc, anchors]], # Detect(P3, P4, P5) 48 | ] 49 | -------------------------------------------------------------------------------- /src/models/yolov5s.yaml: -------------------------------------------------------------------------------- 1 | # parameters 2 | nc: 80 # number of classes 3 | depth_multiple: 0.33 # model depth multiple 4 | width_multiple: 0.50 # layer channel multiple 5 | 6 | # anchors 7 | anchors: 8 | - [10,13, 16,30, 33,23] # P3/8 9 | - [30,61, 62,45, 59,119] # P4/16 10 | - [116,90, 156,198, 373,326] # P5/32 11 | 12 | # YOLOv5 backbone 13 | backbone: 14 | # [from, number, module, args] 15 | [[-1, 1, Focus, [64, 3]], # 0-P1/2 16 | [-1, 1, Conv, [128, 3, 2]], # 1-P2/4 17 | [-1, 3, C3, [128]], 18 | [-1, 1, Conv, [256, 3, 2]], # 3-P3/8 19 | [-1, 9, C3, [256]], 20 | [-1, 1, Conv, [512, 3, 2]], # 5-P4/16 21 | [-1, 9, C3, [512]], 22 | [-1, 1, Conv, [1024, 3, 2]], # 7-P5/32 23 | [-1, 1, SPP, [1024, [5, 9, 13]]], 24 | [-1, 3, C3, [1024, False]], # 9 25 | ] 26 | 27 | # YOLOv5 head 28 | head: 29 | [[-1, 1, Conv, [512, 1, 1]], 30 | [-1, 1, nn.Upsample, [None, 2, 'nearest']], 31 | [[-1, 6], 1, Concat, [1]], # cat backbone P4 32 | [-1, 3, C3, [512, False]], # 13 33 | 34 | [-1, 1, Conv, [256, 1, 1]], 35 | [-1, 1, nn.Upsample, [None, 2, 'nearest']], 36 | [[-1, 4], 1, Concat, [1]], # cat backbone P3 37 | [-1, 3, C3, [256, False]], # 17 (P3/8-small) 38 | 39 | [-1, 1, Conv, [256, 3, 2]], 40 | [[-1, 14], 1, Concat, [1]], # cat head P4 41 | [-1, 3, C3, [512, False]], # 20 (P4/16-medium) 42 | 43 | [-1, 1, Conv, [512, 3, 2]], 44 | [[-1, 10], 1, Concat, [1]], # cat head P5 45 | [-1, 3, C3, [1024, False]], # 23 (P5/32-large) 46 | 47 | [[17, 20, 23], 1, Detect, [nc, anchors]], # Detect(P3, P4, P5) 48 | ] 49 | -------------------------------------------------------------------------------- /src/models/yolov5x.yaml: -------------------------------------------------------------------------------- 1 | # parameters 2 | nc: 80 # number of classes 3 | depth_multiple: 1.33 # model depth multiple 4 | width_multiple: 1.25 # layer channel multiple 5 | 6 | # anchors 7 | anchors: 8 | - [10,13, 16,30, 33,23] # P3/8 9 | - [30,61, 62,45, 59,119] # P4/16 10 | - [116,90, 156,198, 373,326] # P5/32 11 | 12 | # YOLOv5 backbone 13 | backbone: 14 | # [from, number, module, args] 15 | [[-1, 1, Focus, [64, 3]], # 0-P1/2 16 | [-1, 1, Conv, [128, 3, 2]], # 1-P2/4 17 | [-1, 3, C3, [128]], 18 | [-1, 1, Conv, [256, 3, 2]], # 3-P3/8 19 | [-1, 9, C3, [256]], 20 | [-1, 1, Conv, [512, 3, 2]], # 5-P4/16 21 | [-1, 9, C3, [512]], 22 | [-1, 1, Conv, [1024, 3, 2]], # 7-P5/32 23 | [-1, 1, SPP, [1024, [5, 9, 13]]], 24 | [-1, 3, C3, [1024, False]], # 9 25 | ] 26 | 27 | # YOLOv5 head 28 | head: 29 | [[-1, 1, Conv, [512, 1, 1]], 30 | [-1, 1, nn.Upsample, [None, 2, 'nearest']], 31 | [[-1, 6], 1, Concat, [1]], # cat backbone P4 32 | [-1, 3, C3, [512, False]], # 13 33 | 34 | [-1, 1, Conv, [256, 1, 1]], 35 | [-1, 1, nn.Upsample, [None, 2, 'nearest']], 36 | [[-1, 4], 1, Concat, [1]], # cat backbone P3 37 | [-1, 3, C3, [256, False]], # 17 (P3/8-small) 38 | 39 | [-1, 1, Conv, [256, 3, 2]], 40 | [[-1, 14], 1, Concat, [1]], # cat head P4 41 | [-1, 3, C3, [512, False]], # 20 (P4/16-medium) 42 | 43 | [-1, 1, Conv, [512, 3, 2]], 44 | [[-1, 10], 1, Concat, [1]], # cat head P5 45 | [-1, 3, C3, [1024, False]], # 23 (P5/32-large) 46 | 47 | [[17, 20, 23], 1, Detect, [nc, anchors]], # Detect(P3, P4, P5) 48 | ] 49 | -------------------------------------------------------------------------------- /src/utils/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/raghavauppuluri13/yolov5_pytorch_ros/fbd8c5d8aa5bcead2ff02445909624924ceb2026/src/utils/__init__.py -------------------------------------------------------------------------------- /src/utils/activations.py: -------------------------------------------------------------------------------- 1 | # Activation functions 2 | 3 | import torch 4 | import torch.nn as nn 5 | import torch.nn.functional as F 6 | 7 | 8 | # SiLU https://arxiv.org/pdf/1606.08415.pdf ---------------------------------------------------------------------------- 9 | class SiLU(nn.Module): # export-friendly version of nn.SiLU() 10 | @staticmethod 11 | def forward(x): 12 | return x * torch.sigmoid(x) 13 | 14 | 15 | class Hardswish(nn.Module): # export-friendly version of nn.Hardswish() 16 | @staticmethod 17 | def forward(x): 18 | # return x * F.hardsigmoid(x) # for torchscript and CoreML 19 | return x * F.hardtanh(x + 3, 0., 6.) / 6. # for torchscript, CoreML and ONNX 20 | 21 | 22 | class MemoryEfficientSwish(nn.Module): 23 | class F(torch.autograd.Function): 24 | @staticmethod 25 | def forward(ctx, x): 26 | ctx.save_for_backward(x) 27 | return x * torch.sigmoid(x) 28 | 29 | @staticmethod 30 | def backward(ctx, grad_output): 31 | x = ctx.saved_tensors[0] 32 | sx = torch.sigmoid(x) 33 | return grad_output * (sx * (1 + x * (1 - sx))) 34 | 35 | def forward(self, x): 36 | return self.F.apply(x) 37 | 38 | 39 | # Mish https://github.com/digantamisra98/Mish -------------------------------------------------------------------------- 40 | class Mish(nn.Module): 41 | @staticmethod 42 | def forward(x): 43 | return x * F.softplus(x).tanh() 44 | 45 | 46 | class MemoryEfficientMish(nn.Module): 47 | class F(torch.autograd.Function): 48 | @staticmethod 49 | def forward(ctx, x): 50 | ctx.save_for_backward(x) 51 | return x.mul(torch.tanh(F.softplus(x))) # x * tanh(ln(1 + exp(x))) 52 | 53 | @staticmethod 54 | def backward(ctx, grad_output): 55 | x = ctx.saved_tensors[0] 56 | sx = torch.sigmoid(x) 57 | fx = F.softplus(x).tanh() 58 | return grad_output * (fx + x * sx * (1 - fx * fx)) 59 | 60 | def forward(self, x): 61 | return self.F.apply(x) 62 | 63 | 64 | # FReLU https://arxiv.org/abs/2007.11824 ------------------------------------------------------------------------------- 65 | class FReLU(nn.Module): 66 | def __init__(self, c1, k=3): # ch_in, kernel 67 | super().__init__() 68 | self.conv = nn.Conv2d(c1, c1, k, 1, 1, groups=c1, bias=False) 69 | self.bn = nn.BatchNorm2d(c1) 70 | 71 | def forward(self, x): 72 | return torch.max(x, self.bn(self.conv(x))) 73 | -------------------------------------------------------------------------------- /src/utils/autoanchor.py: -------------------------------------------------------------------------------- 1 | # Auto-anchor utils 2 | 3 | import numpy as np 4 | import torch 5 | import yaml 6 | from scipy.cluster.vq import kmeans 7 | from tqdm import tqdm 8 | 9 | from utils.general import colorstr 10 | 11 | 12 | def check_anchor_order(m): 13 | # Check anchor order against stride order for YOLOv5 Detect() module m, and correct if necessary 14 | a = m.anchor_grid.prod(-1).view(-1) # anchor area 15 | da = a[-1] - a[0] # delta a 16 | ds = m.stride[-1] - m.stride[0] # delta s 17 | if da.sign() != ds.sign(): # same order 18 | print('Reversing anchor order') 19 | m.anchors[:] = m.anchors.flip(0) 20 | m.anchor_grid[:] = m.anchor_grid.flip(0) 21 | 22 | 23 | def check_anchors(dataset, model, thr=4.0, imgsz=640): 24 | # Check anchor fit to data, recompute if necessary 25 | prefix = colorstr('autoanchor: ') 26 | print(f'\n{prefix}Analyzing anchors... ', end='') 27 | m = model.module.model[-1] if hasattr(model, 'module') else model.model[-1] # Detect() 28 | shapes = imgsz * dataset.shapes / dataset.shapes.max(1, keepdims=True) 29 | scale = np.random.uniform(0.9, 1.1, size=(shapes.shape[0], 1)) # augment scale 30 | wh = torch.tensor(np.concatenate([l[:, 3:5] * s for s, l in zip(shapes * scale, dataset.labels)])).float() # wh 31 | 32 | def metric(k): # compute metric 33 | r = wh[:, None] / k[None] 34 | x = torch.min(r, 1. / r).min(2)[0] # ratio metric 35 | best = x.max(1)[0] # best_x 36 | aat = (x > 1. / thr).float().sum(1).mean() # anchors above threshold 37 | bpr = (best > 1. / thr).float().mean() # best possible recall 38 | return bpr, aat 39 | 40 | bpr, aat = metric(m.anchor_grid.clone().cpu().view(-1, 2)) 41 | print(f'anchors/target = {aat:.2f}, Best Possible Recall (BPR) = {bpr:.4f}', end='') 42 | if bpr < 0.98: # threshold to recompute 43 | print('. Attempting to improve anchors, please wait...') 44 | na = m.anchor_grid.numel() // 2 # number of anchors 45 | new_anchors = kmean_anchors(dataset, n=na, img_size=imgsz, thr=thr, gen=1000, verbose=False) 46 | new_bpr = metric(new_anchors.reshape(-1, 2))[0] 47 | if new_bpr > bpr: # replace anchors 48 | new_anchors = torch.tensor(new_anchors, device=m.anchors.device).type_as(m.anchors) 49 | m.anchor_grid[:] = new_anchors.clone().view_as(m.anchor_grid) # for inference 50 | m.anchors[:] = new_anchors.clone().view_as(m.anchors) / m.stride.to(m.anchors.device).view(-1, 1, 1) # loss 51 | check_anchor_order(m) 52 | print(f'{prefix}New anchors saved to model. Update model *.yaml to use these anchors in the future.') 53 | else: 54 | print(f'{prefix}Original anchors better than new anchors. Proceeding with original anchors.') 55 | print('') # newline 56 | 57 | 58 | def kmean_anchors(path='./data/coco128.yaml', n=9, img_size=640, thr=4.0, gen=1000, verbose=True): 59 | """ Creates kmeans-evolved anchors from training dataset 60 | 61 | Arguments: 62 | path: path to dataset *.yaml, or a loaded dataset 63 | n: number of anchors 64 | img_size: image size used for training 65 | thr: anchor-label wh ratio threshold hyperparameter hyp['anchor_t'] used for training, default=4.0 66 | gen: generations to evolve anchors using genetic algorithm 67 | verbose: print all results 68 | 69 | Return: 70 | k: kmeans evolved anchors 71 | 72 | Usage: 73 | from utils.autoanchor import *; _ = kmean_anchors() 74 | """ 75 | thr = 1. / thr 76 | prefix = colorstr('autoanchor: ') 77 | 78 | def metric(k, wh): # compute metrics 79 | r = wh[:, None] / k[None] 80 | x = torch.min(r, 1. / r).min(2)[0] # ratio metric 81 | # x = wh_iou(wh, torch.tensor(k)) # iou metric 82 | return x, x.max(1)[0] # x, best_x 83 | 84 | def anchor_fitness(k): # mutation fitness 85 | _, best = metric(torch.tensor(k, dtype=torch.float32), wh) 86 | return (best * (best > thr).float()).mean() # fitness 87 | 88 | def print_results(k): 89 | k = k[np.argsort(k.prod(1))] # sort small to large 90 | x, best = metric(k, wh0) 91 | bpr, aat = (best > thr).float().mean(), (x > thr).float().mean() * n # best possible recall, anch > thr 92 | print(f'{prefix}thr={thr:.2f}: {bpr:.4f} best possible recall, {aat:.2f} anchors past thr') 93 | print(f'{prefix}n={n}, img_size={img_size}, metric_all={x.mean():.3f}/{best.mean():.3f}-mean/best, ' 94 | f'past_thr={x[x > thr].mean():.3f}-mean: ', end='') 95 | for i, x in enumerate(k): 96 | print('%i,%i' % (round(x[0]), round(x[1])), end=', ' if i < len(k) - 1 else '\n') # use in *.cfg 97 | return k 98 | 99 | if isinstance(path, str): # *.yaml file 100 | with open(path) as f: 101 | data_dict = yaml.load(f, Loader=yaml.SafeLoader) # model dict 102 | from utils.datasets import LoadImagesAndLabels 103 | dataset = LoadImagesAndLabels(data_dict['train'], augment=True, rect=True) 104 | else: 105 | dataset = path # dataset 106 | 107 | # Get label wh 108 | shapes = img_size * dataset.shapes / dataset.shapes.max(1, keepdims=True) 109 | wh0 = np.concatenate([l[:, 3:5] * s for s, l in zip(shapes, dataset.labels)]) # wh 110 | 111 | # Filter 112 | i = (wh0 < 3.0).any(1).sum() 113 | if i: 114 | print(f'{prefix}WARNING: Extremely small objects found. {i} of {len(wh0)} labels are < 3 pixels in size.') 115 | wh = wh0[(wh0 >= 2.0).any(1)] # filter > 2 pixels 116 | # wh = wh * (np.random.rand(wh.shape[0], 1) * 0.9 + 0.1) # multiply by random scale 0-1 117 | 118 | # Kmeans calculation 119 | print(f'{prefix}Running kmeans for {n} anchors on {len(wh)} points...') 120 | s = wh.std(0) # sigmas for whitening 121 | k, dist = kmeans(wh / s, n, iter=30) # points, mean distance 122 | k *= s 123 | wh = torch.tensor(wh, dtype=torch.float32) # filtered 124 | wh0 = torch.tensor(wh0, dtype=torch.float32) # unfiltered 125 | k = print_results(k) 126 | 127 | # Plot 128 | # k, d = [None] * 20, [None] * 20 129 | # for i in tqdm(range(1, 21)): 130 | # k[i-1], d[i-1] = kmeans(wh / s, i) # points, mean distance 131 | # fig, ax = plt.subplots(1, 2, figsize=(14, 7), tight_layout=True) 132 | # ax = ax.ravel() 133 | # ax[0].plot(np.arange(1, 21), np.array(d) ** 2, marker='.') 134 | # fig, ax = plt.subplots(1, 2, figsize=(14, 7)) # plot wh 135 | # ax[0].hist(wh[wh[:, 0]<100, 0],400) 136 | # ax[1].hist(wh[wh[:, 1]<100, 1],400) 137 | # fig.savefig('wh.png', dpi=200) 138 | 139 | # Evolve 140 | npr = np.random 141 | f, sh, mp, s = anchor_fitness(k), k.shape, 0.9, 0.1 # fitness, generations, mutation prob, sigma 142 | pbar = tqdm(range(gen), desc=f'{prefix}Evolving anchors with Genetic Algorithm:') # progress bar 143 | for _ in pbar: 144 | v = np.ones(sh) 145 | while (v == 1).all(): # mutate until a change occurs (prevent duplicates) 146 | v = ((npr.random(sh) < mp) * npr.random() * npr.randn(*sh) * s + 1).clip(0.3, 3.0) 147 | kg = (k.copy() * v).clip(min=2.0) 148 | fg = anchor_fitness(kg) 149 | if fg > f: 150 | f, k = fg, kg.copy() 151 | pbar.desc = f'{prefix}Evolving anchors with Genetic Algorithm: fitness = {f:.4f}' 152 | if verbose: 153 | print_results(k) 154 | 155 | return print_results(k) 156 | -------------------------------------------------------------------------------- /src/utils/general.py: -------------------------------------------------------------------------------- 1 | # General utils 2 | 3 | import glob 4 | import logging 5 | import math 6 | import os 7 | import platform 8 | import random 9 | import re 10 | import subprocess 11 | import time 12 | from pathlib import Path 13 | 14 | import cv2 15 | import numpy as np 16 | import torch 17 | import torchvision 18 | import yaml 19 | 20 | from utils.google_utils import gsutil_getsize 21 | from utils.metrics import fitness 22 | from utils.torch_utils import init_torch_seeds 23 | 24 | # Settings 25 | torch.set_printoptions(linewidth=320, precision=5, profile='long') 26 | np.set_printoptions(linewidth=320, formatter={'float_kind': '{:11.5g}'.format}) # format short g, %precision=5 27 | cv2.setNumThreads(0) # prevent OpenCV from multithreading (incompatible with PyTorch DataLoader) 28 | os.environ['NUMEXPR_MAX_THREADS'] = str(min(os.cpu_count(), 8)) # NumExpr max threads 29 | 30 | 31 | def set_logging(rank=-1): 32 | logging.basicConfig( 33 | format="%(message)s", 34 | level=logging.INFO if rank in [-1, 0] else logging.WARN) 35 | 36 | 37 | def init_seeds(seed=0): 38 | # Initialize random number generator (RNG) seeds 39 | random.seed(seed) 40 | np.random.seed(seed) 41 | init_torch_seeds(seed) 42 | 43 | 44 | def get_latest_run(search_dir='.'): 45 | # Return path to most recent 'last.pt' in /runs (i.e. to --resume from) 46 | last_list = glob.glob(f'{search_dir}/**/last*.pt', recursive=True) 47 | return max(last_list, key=os.path.getctime) if last_list else '' 48 | 49 | 50 | def check_online(): 51 | # Check internet connectivity 52 | import socket 53 | try: 54 | socket.create_connection(("1.1.1.1", 443), 5) # check host accesability 55 | return True 56 | except OSError: 57 | return False 58 | 59 | 60 | def check_git_status(): 61 | # Recommend 'git pull' if code is out of date 62 | print(colorstr('github: '), end='') 63 | try: 64 | assert Path('.git').exists(), 'skipping check (not a git repository)' 65 | assert not Path('/workspace').exists(), 'skipping check (Docker image)' # not Path('/.dockerenv').exists() 66 | assert check_online(), 'skipping check (offline)' 67 | 68 | cmd = 'git fetch && git config --get remote.origin.url' 69 | url = subprocess.check_output(cmd, shell=True).decode().strip().rstrip('.git') # github repo url 70 | branch = subprocess.check_output('git rev-parse --abbrev-ref HEAD', shell=True).decode().strip() # checked out 71 | n = int(subprocess.check_output(f'git rev-list {branch}..origin/master --count', shell=True)) # commits behind 72 | if n > 0: 73 | s = f"⚠️ WARNING: code is out of date by {n} commit{'s' * (n > 1)}. " \ 74 | f"Use 'git pull' to update or 'git clone {url}' to download latest." 75 | else: 76 | s = f'up to date with {url} ✅' 77 | print(s.encode().decode('ascii', 'ignore') if platform.system() == 'Windows' else s) 78 | except Exception as e: 79 | print(e) 80 | 81 | 82 | def check_requirements(file='requirements.txt', exclude=()): 83 | # Check installed dependencies meet requirements 84 | import pkg_resources 85 | requirements = [f'{x.name}{x.specifier}' for x in pkg_resources.parse_requirements(Path(file).open()) 86 | if x.name not in exclude] 87 | pkg_resources.require(requirements) # DistributionNotFound or VersionConflict exception if requirements not met 88 | 89 | 90 | def check_img_size(img_size, s=32): 91 | # Verify img_size is a multiple of stride s 92 | new_size = make_divisible(img_size, int(s)) # ceil gs-multiple 93 | if new_size != img_size: 94 | print('WARNING: --img-size %g must be multiple of max stride %g, updating to %g' % (img_size, s, new_size)) 95 | return new_size 96 | 97 | 98 | def check_file(file): 99 | # Search for file if not found 100 | if os.path.isfile(file) or file == '': 101 | return file 102 | else: 103 | files = glob.glob('./**/' + file, recursive=True) # find file 104 | assert len(files), 'File Not Found: %s' % file # assert file was found 105 | assert len(files) == 1, "Multiple files match '%s', specify exact path: %s" % (file, files) # assert unique 106 | return files[0] # return file 107 | 108 | 109 | def check_dataset(dict): 110 | # Download dataset if not found locally 111 | val, s = dict.get('val'), dict.get('download') 112 | if val and len(val): 113 | val = [Path(x).resolve() for x in (val if isinstance(val, list) else [val])] # val path 114 | if not all(x.exists() for x in val): 115 | print('\nWARNING: Dataset not found, nonexistent paths: %s' % [str(x) for x in val if not x.exists()]) 116 | if s and len(s): # download script 117 | print('Downloading %s ...' % s) 118 | if s.startswith('http') and s.endswith('.zip'): # URL 119 | f = Path(s).name # filename 120 | torch.hub.download_url_to_file(s, f) 121 | r = os.system('unzip -q %s -d ../ && rm %s' % (f, f)) # unzip 122 | else: # bash script 123 | r = os.system(s) 124 | print('Dataset autodownload %s\n' % ('success' if r == 0 else 'failure')) # analyze return value 125 | else: 126 | raise Exception('Dataset not found.') 127 | 128 | 129 | def make_divisible(x, divisor): 130 | # Returns x evenly divisible by divisor 131 | return math.ceil(x / divisor) * divisor 132 | 133 | 134 | def clean_str(s): 135 | # Cleans a string by replacing special characters with underscore _ 136 | return re.sub(pattern="[|@#!¡·$€%&()=?¿^*;:,¨´><+]", repl="_", string=s) 137 | 138 | 139 | def one_cycle(y1=0.0, y2=1.0, steps=100): 140 | # lambda function for sinusoidal ramp from y1 to y2 141 | return lambda x: ((1 - math.cos(x * math.pi / steps)) / 2) * (y2 - y1) + y1 142 | 143 | 144 | def colorstr(*input): 145 | # Colors a string https://en.wikipedia.org/wiki/ANSI_escape_code, i.e. colorstr('blue', 'hello world') 146 | *args, string = input if len(input) > 1 else ('blue', 'bold', input[0]) # color arguments, string 147 | colors = {'black': '\033[30m', # basic colors 148 | 'red': '\033[31m', 149 | 'green': '\033[32m', 150 | 'yellow': '\033[33m', 151 | 'blue': '\033[34m', 152 | 'magenta': '\033[35m', 153 | 'cyan': '\033[36m', 154 | 'white': '\033[37m', 155 | 'bright_black': '\033[90m', # bright colors 156 | 'bright_red': '\033[91m', 157 | 'bright_green': '\033[92m', 158 | 'bright_yellow': '\033[93m', 159 | 'bright_blue': '\033[94m', 160 | 'bright_magenta': '\033[95m', 161 | 'bright_cyan': '\033[96m', 162 | 'bright_white': '\033[97m', 163 | 'end': '\033[0m', # misc 164 | 'bold': '\033[1m', 165 | 'underline': '\033[4m'} 166 | return ''.join(colors[x] for x in args) + f'{string}' + colors['end'] 167 | 168 | 169 | def labels_to_class_weights(labels, nc=80): 170 | # Get class weights (inverse frequency) from training labels 171 | if labels[0] is None: # no labels loaded 172 | return torch.Tensor() 173 | 174 | labels = np.concatenate(labels, 0) # labels.shape = (866643, 5) for COCO 175 | classes = labels[:, 0].astype(np.int) # labels = [class xywh] 176 | weights = np.bincount(classes, minlength=nc) # occurrences per class 177 | 178 | # Prepend gridpoint count (for uCE training) 179 | # gpi = ((320 / 32 * np.array([1, 2, 4])) ** 2 * 3).sum() # gridpoints per image 180 | # weights = np.hstack([gpi * len(labels) - weights.sum() * 9, weights * 9]) ** 0.5 # prepend gridpoints to start 181 | 182 | weights[weights == 0] = 1 # replace empty bins with 1 183 | weights = 1 / weights # number of targets per class 184 | weights /= weights.sum() # normalize 185 | return torch.from_numpy(weights) 186 | 187 | 188 | def labels_to_image_weights(labels, nc=80, class_weights=np.ones(80)): 189 | # Produces image weights based on class_weights and image contents 190 | class_counts = np.array([np.bincount(x[:, 0].astype(np.int), minlength=nc) for x in labels]) 191 | image_weights = (class_weights.reshape(1, nc) * class_counts).sum(1) 192 | # index = random.choices(range(n), weights=image_weights, k=1) # weight image sample 193 | return image_weights 194 | 195 | 196 | def coco80_to_coco91_class(): # converts 80-index (val2014) to 91-index (paper) 197 | # https://tech.amikelive.com/node-718/what-object-categories-labels-are-in-coco-dataset/ 198 | # a = np.loadtxt('data/coco.names', dtype='str', delimiter='\n') 199 | # b = np.loadtxt('data/coco_paper.names', dtype='str', delimiter='\n') 200 | # x1 = [list(a[i] == b).index(True) + 1 for i in range(80)] # darknet to coco 201 | # x2 = [list(b[i] == a).index(True) if any(b[i] == a) else None for i in range(91)] # coco to darknet 202 | x = [1, 2, 3, 4, 5, 6, 7, 8, 9, 10, 11, 13, 14, 15, 16, 17, 18, 19, 20, 21, 22, 23, 24, 25, 27, 28, 31, 32, 33, 34, 203 | 35, 36, 37, 38, 39, 40, 41, 42, 43, 44, 46, 47, 48, 49, 50, 51, 52, 53, 54, 55, 56, 57, 58, 59, 60, 61, 62, 63, 204 | 64, 65, 67, 70, 72, 73, 74, 75, 76, 77, 78, 79, 80, 81, 82, 84, 85, 86, 87, 88, 89, 90] 205 | return x 206 | 207 | 208 | def xyxy2xywh(x): 209 | # Convert nx4 boxes from [x1, y1, x2, y2] to [x, y, w, h] where xy1=top-left, xy2=bottom-right 210 | y = x.clone() if isinstance(x, torch.Tensor) else np.copy(x) 211 | y[:, 0] = (x[:, 0] + x[:, 2]) / 2 # x center 212 | y[:, 1] = (x[:, 1] + x[:, 3]) / 2 # y center 213 | y[:, 2] = x[:, 2] - x[:, 0] # width 214 | y[:, 3] = x[:, 3] - x[:, 1] # height 215 | return y 216 | 217 | 218 | def xywh2xyxy(x): 219 | # Convert nx4 boxes from [x, y, w, h] to [x1, y1, x2, y2] where xy1=top-left, xy2=bottom-right 220 | y = x.clone() if isinstance(x, torch.Tensor) else np.copy(x) 221 | y[:, 0] = x[:, 0] - x[:, 2] / 2 # top left x 222 | y[:, 1] = x[:, 1] - x[:, 3] / 2 # top left y 223 | y[:, 2] = x[:, 0] + x[:, 2] / 2 # bottom right x 224 | y[:, 3] = x[:, 1] + x[:, 3] / 2 # bottom right y 225 | return y 226 | 227 | 228 | def xywhn2xyxy(x, w=640, h=640, padw=0, padh=0): 229 | # Convert nx4 boxes from [x, y, w, h] normalized to [x1, y1, x2, y2] where xy1=top-left, xy2=bottom-right 230 | y = x.clone() if isinstance(x, torch.Tensor) else np.copy(x) 231 | y[:, 0] = w * (x[:, 0] - x[:, 2] / 2) + padw # top left x 232 | y[:, 1] = h * (x[:, 1] - x[:, 3] / 2) + padh # top left y 233 | y[:, 2] = w * (x[:, 0] + x[:, 2] / 2) + padw # bottom right x 234 | y[:, 3] = h * (x[:, 1] + x[:, 3] / 2) + padh # bottom right y 235 | return y 236 | 237 | 238 | def xyn2xy(x, w=640, h=640, padw=0, padh=0): 239 | # Convert normalized segments into pixel segments, shape (n,2) 240 | y = x.clone() if isinstance(x, torch.Tensor) else np.copy(x) 241 | y[:, 0] = w * x[:, 0] + padw # top left x 242 | y[:, 1] = h * x[:, 1] + padh # top left y 243 | return y 244 | 245 | 246 | def segment2box(segment, width=640, height=640): 247 | # Convert 1 segment label to 1 box label, applying inside-image constraint, i.e. (xy1, xy2, ...) to (xyxy) 248 | x, y = segment.T # segment xy 249 | inside = (x >= 0) & (y >= 0) & (x <= width) & (y <= height) 250 | x, y, = x[inside], y[inside] 251 | return np.array([x.min(), y.min(), x.max(), y.max()]) if any(x) else np.zeros((1, 4)) # cls, xyxy 252 | 253 | 254 | def segments2boxes(segments): 255 | # Convert segment labels to box labels, i.e. (cls, xy1, xy2, ...) to (cls, xywh) 256 | boxes = [] 257 | for s in segments: 258 | x, y = s.T # segment xy 259 | boxes.append([x.min(), y.min(), x.max(), y.max()]) # cls, xyxy 260 | return xyxy2xywh(np.array(boxes)) # cls, xywh 261 | 262 | 263 | def resample_segments(segments, n=1000): 264 | # Up-sample an (n,2) segment 265 | for i, s in enumerate(segments): 266 | x = np.linspace(0, len(s) - 1, n) 267 | xp = np.arange(len(s)) 268 | segments[i] = np.concatenate([np.interp(x, xp, s[:, i]) for i in range(2)]).reshape(2, -1).T # segment xy 269 | return segments 270 | 271 | 272 | def scale_coords(img1_shape, coords, img0_shape, ratio_pad=None): 273 | # Rescale coords (xyxy) from img1_shape to img0_shape 274 | if ratio_pad is None: # calculate from img0_shape 275 | gain = min(img1_shape[0] / img0_shape[0], img1_shape[1] / img0_shape[1]) # gain = old / new 276 | pad = (img1_shape[1] - img0_shape[1] * gain) / 2, (img1_shape[0] - img0_shape[0] * gain) / 2 # wh padding 277 | else: 278 | gain = ratio_pad[0][0] 279 | pad = ratio_pad[1] 280 | 281 | coords[:, [0, 2]] -= pad[0] # x padding 282 | coords[:, [1, 3]] -= pad[1] # y padding 283 | coords[:, :4] /= gain 284 | clip_coords(coords, img0_shape) 285 | return coords 286 | 287 | 288 | def clip_coords(boxes, img_shape): 289 | # Clip bounding xyxy bounding boxes to image shape (height, width) 290 | boxes[:, 0].clamp_(0, img_shape[1]) # x1 291 | boxes[:, 1].clamp_(0, img_shape[0]) # y1 292 | boxes[:, 2].clamp_(0, img_shape[1]) # x2 293 | boxes[:, 3].clamp_(0, img_shape[0]) # y2 294 | 295 | 296 | def bbox_iou(box1, box2, x1y1x2y2=True, GIoU=False, DIoU=False, CIoU=False, eps=1e-9): 297 | # Returns the IoU of box1 to box2. box1 is 4, box2 is nx4 298 | box2 = box2.T 299 | 300 | # Get the coordinates of bounding boxes 301 | if x1y1x2y2: # x1, y1, x2, y2 = box1 302 | b1_x1, b1_y1, b1_x2, b1_y2 = box1[0], box1[1], box1[2], box1[3] 303 | b2_x1, b2_y1, b2_x2, b2_y2 = box2[0], box2[1], box2[2], box2[3] 304 | else: # transform from xywh to xyxy 305 | b1_x1, b1_x2 = box1[0] - box1[2] / 2, box1[0] + box1[2] / 2 306 | b1_y1, b1_y2 = box1[1] - box1[3] / 2, box1[1] + box1[3] / 2 307 | b2_x1, b2_x2 = box2[0] - box2[2] / 2, box2[0] + box2[2] / 2 308 | b2_y1, b2_y2 = box2[1] - box2[3] / 2, box2[1] + box2[3] / 2 309 | 310 | # Intersection area 311 | inter = (torch.min(b1_x2, b2_x2) - torch.max(b1_x1, b2_x1)).clamp(0) * \ 312 | (torch.min(b1_y2, b2_y2) - torch.max(b1_y1, b2_y1)).clamp(0) 313 | 314 | # Union Area 315 | w1, h1 = b1_x2 - b1_x1, b1_y2 - b1_y1 + eps 316 | w2, h2 = b2_x2 - b2_x1, b2_y2 - b2_y1 + eps 317 | union = w1 * h1 + w2 * h2 - inter + eps 318 | 319 | iou = inter / union 320 | if GIoU or DIoU or CIoU: 321 | cw = torch.max(b1_x2, b2_x2) - torch.min(b1_x1, b2_x1) # convex (smallest enclosing box) width 322 | ch = torch.max(b1_y2, b2_y2) - torch.min(b1_y1, b2_y1) # convex height 323 | if CIoU or DIoU: # Distance or Complete IoU https://arxiv.org/abs/1911.08287v1 324 | c2 = cw ** 2 + ch ** 2 + eps # convex diagonal squared 325 | rho2 = ((b2_x1 + b2_x2 - b1_x1 - b1_x2) ** 2 + 326 | (b2_y1 + b2_y2 - b1_y1 - b1_y2) ** 2) / 4 # center distance squared 327 | if DIoU: 328 | return iou - rho2 / c2 # DIoU 329 | elif CIoU: # https://github.com/Zzh-tju/DIoU-SSD-pytorch/blob/master/utils/box/box_utils.py#L47 330 | v = (4 / math.pi ** 2) * torch.pow(torch.atan(w2 / h2) - torch.atan(w1 / h1), 2) 331 | with torch.no_grad(): 332 | alpha = v / ((1 + eps) - iou + v) 333 | return iou - (rho2 / c2 + v * alpha) # CIoU 334 | else: # GIoU https://arxiv.org/pdf/1902.09630.pdf 335 | c_area = cw * ch + eps # convex area 336 | return iou - (c_area - union) / c_area # GIoU 337 | else: 338 | return iou # IoU 339 | 340 | 341 | def box_iou(box1, box2): 342 | # https://github.com/pytorch/vision/blob/master/torchvision/ops/boxes.py 343 | """ 344 | Return intersection-over-union (Jaccard index) of boxes. 345 | Both sets of boxes are expected to be in (x1, y1, x2, y2) format. 346 | Arguments: 347 | box1 (Tensor[N, 4]) 348 | box2 (Tensor[M, 4]) 349 | Returns: 350 | iou (Tensor[N, M]): the NxM matrix containing the pairwise 351 | IoU values for every element in boxes1 and boxes2 352 | """ 353 | 354 | def box_area(box): 355 | # box = 4xn 356 | return (box[2] - box[0]) * (box[3] - box[1]) 357 | 358 | area1 = box_area(box1.T) 359 | area2 = box_area(box2.T) 360 | 361 | # inter(N,M) = (rb(N,M,2) - lt(N,M,2)).clamp(0).prod(2) 362 | inter = (torch.min(box1[:, None, 2:], box2[:, 2:]) - torch.max(box1[:, None, :2], box2[:, :2])).clamp(0).prod(2) 363 | return inter / (area1[:, None] + area2 - inter) # iou = inter / (area1 + area2 - inter) 364 | 365 | 366 | def wh_iou(wh1, wh2): 367 | # Returns the nxm IoU matrix. wh1 is nx2, wh2 is mx2 368 | wh1 = wh1[:, None] # [N,1,2] 369 | wh2 = wh2[None] # [1,M,2] 370 | inter = torch.min(wh1, wh2).prod(2) # [N,M] 371 | return inter / (wh1.prod(2) + wh2.prod(2) - inter) # iou = inter / (area1 + area2 - inter) 372 | 373 | 374 | def non_max_suppression(prediction, conf_thres=0.25, iou_thres=0.45, classes=None, agnostic=False, labels=()): 375 | """Performs Non-Maximum Suppression (NMS) on inference results 376 | 377 | Returns: 378 | detections with shape: nx6 (x1, y1, x2, y2, conf, cls) 379 | """ 380 | 381 | nc = prediction.shape[2] - 5 # number of classes 382 | xc = prediction[..., 4] > conf_thres # candidates 383 | 384 | # Settings 385 | min_wh, max_wh = 2, 4096 # (pixels) minimum and maximum box width and height 386 | max_det = 300 # maximum number of detections per image 387 | max_nms = 30000 # maximum number of boxes into torchvision.ops.nms() 388 | time_limit = 10.0 # seconds to quit after 389 | redundant = True # require redundant detections 390 | multi_label = nc > 1 # multiple labels per box (adds 0.5ms/img) 391 | merge = False # use merge-NMS 392 | 393 | t = time.time() 394 | output = [torch.zeros((0, 6), device=prediction.device)] * prediction.shape[0] 395 | for xi, x in enumerate(prediction): # image index, image inference 396 | # Apply constraints 397 | # x[((x[..., 2:4] < min_wh) | (x[..., 2:4] > max_wh)).any(1), 4] = 0 # width-height 398 | x = x[xc[xi]] # confidence 399 | 400 | # Cat apriori labels if autolabelling 401 | if labels and len(labels[xi]): 402 | l = labels[xi] 403 | v = torch.zeros((len(l), nc + 5), device=x.device) 404 | v[:, :4] = l[:, 1:5] # box 405 | v[:, 4] = 1.0 # conf 406 | v[range(len(l)), l[:, 0].long() + 5] = 1.0 # cls 407 | x = torch.cat((x, v), 0) 408 | 409 | # If none remain process next image 410 | if not x.shape[0]: 411 | continue 412 | 413 | # Compute conf 414 | x[:, 5:] *= x[:, 4:5] # conf = obj_conf * cls_conf 415 | 416 | # Box (center x, center y, width, height) to (x1, y1, x2, y2) 417 | box = xywh2xyxy(x[:, :4]) 418 | 419 | # Detections matrix nx6 (xyxy, conf, cls) 420 | if multi_label: 421 | i, j = (x[:, 5:] > conf_thres).nonzero(as_tuple=False).T 422 | x = torch.cat((box[i], x[i, j + 5, None], j[:, None].float()), 1) 423 | else: # best class only 424 | conf, j = x[:, 5:].max(1, keepdim=True) 425 | x = torch.cat((box, conf, j.float()), 1)[conf.view(-1) > conf_thres] 426 | 427 | # Filter by class 428 | if classes is not None: 429 | x = x[(x[:, 5:6] == torch.tensor(classes, device=x.device)).any(1)] 430 | 431 | # Apply finite constraint 432 | # if not torch.isfinite(x).all(): 433 | # x = x[torch.isfinite(x).all(1)] 434 | 435 | # Check shape 436 | n = x.shape[0] # number of boxes 437 | if not n: # no boxes 438 | continue 439 | elif n > max_nms: # excess boxes 440 | x = x[x[:, 4].argsort(descending=True)[:max_nms]] # sort by confidence 441 | 442 | # Batched NMS 443 | c = x[:, 5:6] * (0 if agnostic else max_wh) # classes 444 | boxes, scores = x[:, :4] + c, x[:, 4] # boxes (offset by class), scores 445 | i = torchvision.ops.nms(boxes, scores, iou_thres) # NMS 446 | if i.shape[0] > max_det: # limit detections 447 | i = i[:max_det] 448 | if merge and (1 < n < 3E3): # Merge NMS (boxes merged using weighted mean) 449 | # update boxes as boxes(i,4) = weights(i,n) * boxes(n,4) 450 | iou = box_iou(boxes[i], boxes) > iou_thres # iou matrix 451 | weights = iou * scores[None] # box weights 452 | x[i, :4] = torch.mm(weights, x[:, :4]).float() / weights.sum(1, keepdim=True) # merged boxes 453 | if redundant: 454 | i = i[iou.sum(1) > 1] # require redundancy 455 | 456 | output[xi] = x[i] 457 | if (time.time() - t) > time_limit: 458 | print(f'WARNING: NMS time limit {time_limit}s exceeded') 459 | break # time limit exceeded 460 | 461 | return output 462 | 463 | 464 | def strip_optimizer(f='weights/best.pt', s=''): # from utils.general import *; strip_optimizer() 465 | # Strip optimizer from 'f' to finalize training, optionally save as 's' 466 | x = torch.load(f, map_location=torch.device('cpu')) 467 | for key in 'optimizer', 'training_results', 'wandb_id': 468 | x[key] = None 469 | x['epoch'] = -1 470 | x['model'].half() # to FP16 471 | for p in x['model'].parameters(): 472 | p.requires_grad = False 473 | torch.save(x, s or f) 474 | mb = os.path.getsize(s or f) / 1E6 # filesize 475 | print('Optimizer stripped from %s,%s %.1fMB' % (f, (' saved as %s,' % s) if s else '', mb)) 476 | 477 | 478 | def print_mutation(hyp, results, yaml_file='hyp_evolved.yaml', bucket=''): 479 | # Print mutation results to evolve.txt (for use with train.py --evolve) 480 | a = '%10s' * len(hyp) % tuple(hyp.keys()) # hyperparam keys 481 | b = '%10.3g' * len(hyp) % tuple(hyp.values()) # hyperparam values 482 | c = '%10.4g' * len(results) % results # results (P, R, mAP@0.5, mAP@0.5:0.95, val_losses x 3) 483 | print('\n%s\n%s\nEvolved fitness: %s\n' % (a, b, c)) 484 | 485 | if bucket: 486 | url = 'gs://%s/evolve.txt' % bucket 487 | if gsutil_getsize(url) > (os.path.getsize('evolve.txt') if os.path.exists('evolve.txt') else 0): 488 | os.system('gsutil cp %s .' % url) # download evolve.txt if larger than local 489 | 490 | with open('evolve.txt', 'a') as f: # append result 491 | f.write(c + b + '\n') 492 | x = np.unique(np.loadtxt('evolve.txt', ndmin=2), axis=0) # load unique rows 493 | x = x[np.argsort(-fitness(x))] # sort 494 | np.savetxt('evolve.txt', x, '%10.3g') # save sort by fitness 495 | 496 | # Save yaml 497 | for i, k in enumerate(hyp.keys()): 498 | hyp[k] = float(x[0, i + 7]) 499 | with open(yaml_file, 'w') as f: 500 | results = tuple(x[0, :7]) 501 | c = '%10.4g' * len(results) % results # results (P, R, mAP@0.5, mAP@0.5:0.95, val_losses x 3) 502 | f.write('# Hyperparameter Evolution Results\n# Generations: %g\n# Metrics: ' % len(x) + c + '\n\n') 503 | yaml.dump(hyp, f, sort_keys=False) 504 | 505 | if bucket: 506 | os.system('gsutil cp evolve.txt %s gs://%s' % (yaml_file, bucket)) # upload 507 | 508 | 509 | def apply_classifier(x, model, img, im0): 510 | # applies a second stage classifier to yolo outputs 511 | im0 = [im0] if isinstance(im0, np.ndarray) else im0 512 | for i, d in enumerate(x): # per image 513 | if d is not None and len(d): 514 | d = d.clone() 515 | 516 | # Reshape and pad cutouts 517 | b = xyxy2xywh(d[:, :4]) # boxes 518 | b[:, 2:] = b[:, 2:].max(1)[0].unsqueeze(1) # rectangle to square 519 | b[:, 2:] = b[:, 2:] * 1.3 + 30 # pad 520 | d[:, :4] = xywh2xyxy(b).long() 521 | 522 | # Rescale boxes from img_size to im0 size 523 | scale_coords(img.shape[2:], d[:, :4], im0[i].shape) 524 | 525 | # Classes 526 | pred_cls1 = d[:, 5].long() 527 | ims = [] 528 | for j, a in enumerate(d): # per item 529 | cutout = im0[i][int(a[1]):int(a[3]), int(a[0]):int(a[2])] 530 | im = cv2.resize(cutout, (224, 224)) # BGR 531 | # cv2.imwrite('test%i.jpg' % j, cutout) 532 | 533 | im = im[:, :, ::-1].transpose(2, 0, 1) # BGR to RGB, to 3x416x416 534 | im = np.ascontiguousarray(im, dtype=np.float32) # uint8 to float32 535 | im /= 255.0 # 0 - 255 to 0.0 - 1.0 536 | ims.append(im) 537 | 538 | pred_cls2 = model(torch.Tensor(ims).to(d.device)).argmax(1) # classifier prediction 539 | x[i] = x[i][pred_cls1 == pred_cls2] # retain matching class detections 540 | 541 | return x 542 | 543 | 544 | def increment_path(path, exist_ok=True, sep=''): 545 | # Increment path, i.e. runs/exp --> runs/exp{sep}0, runs/exp{sep}1 etc. 546 | path = Path(path) # os-agnostic 547 | if (path.exists() and exist_ok) or (not path.exists()): 548 | return str(path) 549 | else: 550 | dirs = glob.glob(f"{path}{sep}*") # similar paths 551 | matches = [re.search(rf"%s{sep}(\d+)" % path.stem, d) for d in dirs] 552 | i = [int(m.groups()[0]) for m in matches if m] # indices 553 | n = max(i) + 1 if i else 2 # increment number 554 | return f"{path}{sep}{n}" # update path 555 | -------------------------------------------------------------------------------- /src/utils/google_app_engine/Dockerfile: -------------------------------------------------------------------------------- 1 | FROM gcr.io/google-appengine/python 2 | 3 | # Create a virtualenv for dependencies. This isolates these packages from 4 | # system-level packages. 5 | # Use -p python3 or -p python3.7 to select python version. Default is version 2. 6 | RUN virtualenv /env -p python3 7 | 8 | # Setting these environment variables are the same as running 9 | # source /env/bin/activate. 10 | ENV VIRTUAL_ENV /env 11 | ENV PATH /env/bin:$PATH 12 | 13 | RUN apt-get update && apt-get install -y python-opencv 14 | 15 | # Copy the application's requirements.txt and run pip to install all 16 | # dependencies into the virtualenv. 17 | ADD requirements.txt /app/requirements.txt 18 | RUN pip install -r /app/requirements.txt 19 | 20 | # Add the application source code. 21 | ADD . /app 22 | 23 | # Run a WSGI server to serve the application. gunicorn must be declared as 24 | # a dependency in requirements.txt. 25 | CMD gunicorn -b :$PORT main:app 26 | -------------------------------------------------------------------------------- /src/utils/google_app_engine/additional_requirements.txt: -------------------------------------------------------------------------------- 1 | # add these requirements in your app on top of the existing ones 2 | pip==18.1 3 | Flask==1.0.2 4 | gunicorn==19.9.0 5 | -------------------------------------------------------------------------------- /src/utils/google_app_engine/app.yaml: -------------------------------------------------------------------------------- 1 | runtime: custom 2 | env: flex 3 | 4 | service: yolov5app 5 | 6 | liveness_check: 7 | initial_delay_sec: 600 8 | 9 | manual_scaling: 10 | instances: 1 11 | resources: 12 | cpu: 1 13 | memory_gb: 4 14 | disk_size_gb: 20 -------------------------------------------------------------------------------- /src/utils/google_utils.py: -------------------------------------------------------------------------------- 1 | # Google utils: https://cloud.google.com/storage/docs/reference/libraries 2 | 3 | import os 4 | import platform 5 | import subprocess 6 | import time 7 | from pathlib import Path 8 | 9 | import requests 10 | import torch 11 | 12 | 13 | def gsutil_getsize(url=''): 14 | # gs://bucket/file size https://cloud.google.com/storage/docs/gsutil/commands/du 15 | s = subprocess.check_output(f'gsutil du {url}', shell=True).decode('utf-8') 16 | return eval(s.split(' ')[0]) if len(s) else 0 # bytes 17 | 18 | 19 | def attempt_download(file, repo='ultralytics/yolov5'): 20 | # Attempt file download if does not exist 21 | file = Path(str(file).strip().replace("'", '').lower()) 22 | 23 | if not file.exists(): 24 | try: 25 | response = requests.get(f'https://api.github.com/repos/{repo}/releases/latest').json() # github api 26 | assets = [x['name'] for x in response['assets']] # release assets, i.e. ['yolov5s.pt', 'yolov5m.pt', ...] 27 | tag = response['tag_name'] # i.e. 'v1.0' 28 | except: # fallback plan 29 | assets = ['yolov5s.pt', 'yolov5m.pt', 'yolov5l.pt', 'yolov5x.pt'] 30 | tag = subprocess.check_output('git tag', shell=True).decode().split()[-1] 31 | 32 | name = file.name 33 | if name in assets: 34 | msg = f'{file} missing, try downloading from https://github.com/{repo}/releases/' 35 | redundant = False # second download option 36 | try: # GitHub 37 | url = f'https://github.com/{repo}/releases/download/{tag}/{name}' 38 | print(f'Downloading {url} to {file}...') 39 | torch.hub.download_url_to_file(url, file) 40 | assert file.exists() and file.stat().st_size > 1E6 # check 41 | except Exception as e: # GCP 42 | print(f'Download error: {e}') 43 | assert redundant, 'No secondary mirror' 44 | url = f'https://storage.googleapis.com/{repo}/ckpt/{name}' 45 | print(f'Downloading {url} to {file}...') 46 | os.system(f'curl -L {url} -o {file}') # torch.hub.download_url_to_file(url, weights) 47 | finally: 48 | if not file.exists() or file.stat().st_size < 1E6: # check 49 | file.unlink(missing_ok=True) # remove partial downloads 50 | print(f'ERROR: Download failure: {msg}') 51 | print('') 52 | return 53 | 54 | 55 | def gdrive_download(id='16TiPfZj7htmTyhntwcZyEEAejOUxuT6m', file='tmp.zip'): 56 | # Downloads a file from Google Drive. from yolov5.utils.google_utils import *; gdrive_download() 57 | t = time.time() 58 | file = Path(file) 59 | cookie = Path('cookie') # gdrive cookie 60 | print(f'Downloading https://drive.google.com/uc?export=download&id={id} as {file}... ', end='') 61 | file.unlink(missing_ok=True) # remove existing file 62 | cookie.unlink(missing_ok=True) # remove existing cookie 63 | 64 | # Attempt file download 65 | out = "NUL" if platform.system() == "Windows" else "/dev/null" 66 | os.system(f'curl -c ./cookie -s -L "drive.google.com/uc?export=download&id={id}" > {out}') 67 | if os.path.exists('cookie'): # large file 68 | s = f'curl -Lb ./cookie "drive.google.com/uc?export=download&confirm={get_token()}&id={id}" -o {file}' 69 | else: # small file 70 | s = f'curl -s -L -o {file} "drive.google.com/uc?export=download&id={id}"' 71 | r = os.system(s) # execute, capture return 72 | cookie.unlink(missing_ok=True) # remove existing cookie 73 | 74 | # Error check 75 | if r != 0: 76 | file.unlink(missing_ok=True) # remove partial 77 | print('Download error ') # raise Exception('Download error') 78 | return r 79 | 80 | # Unzip if archive 81 | if file.suffix == '.zip': 82 | print('unzipping... ', end='') 83 | os.system(f'unzip -q {file}') # unzip 84 | file.unlink() # remove zip to free space 85 | 86 | print(f'Done ({time.time() - t:.1f}s)') 87 | return r 88 | 89 | 90 | def get_token(cookie="./cookie"): 91 | with open(cookie) as f: 92 | for line in f: 93 | if "download" in line: 94 | return line.split()[-1] 95 | return "" 96 | 97 | # def upload_blob(bucket_name, source_file_name, destination_blob_name): 98 | # # Uploads a file to a bucket 99 | # # https://cloud.google.com/storage/docs/uploading-objects#storage-upload-object-python 100 | # 101 | # storage_client = storage.Client() 102 | # bucket = storage_client.get_bucket(bucket_name) 103 | # blob = bucket.blob(destination_blob_name) 104 | # 105 | # blob.upload_from_filename(source_file_name) 106 | # 107 | # print('File {} uploaded to {}.'.format( 108 | # source_file_name, 109 | # destination_blob_name)) 110 | # 111 | # 112 | # def download_blob(bucket_name, source_blob_name, destination_file_name): 113 | # # Uploads a blob from a bucket 114 | # storage_client = storage.Client() 115 | # bucket = storage_client.get_bucket(bucket_name) 116 | # blob = bucket.blob(source_blob_name) 117 | # 118 | # blob.download_to_filename(destination_file_name) 119 | # 120 | # print('Blob {} downloaded to {}.'.format( 121 | # source_blob_name, 122 | # destination_file_name)) 123 | -------------------------------------------------------------------------------- /src/utils/loss.py: -------------------------------------------------------------------------------- 1 | # Loss functions 2 | 3 | import torch 4 | import torch.nn as nn 5 | 6 | from utils.general import bbox_iou 7 | from utils.torch_utils import is_parallel 8 | 9 | 10 | def smooth_BCE(eps=0.1): # https://github.com/ultralytics/yolov3/issues/238#issuecomment-598028441 11 | # return positive, negative label smoothing BCE targets 12 | return 1.0 - 0.5 * eps, 0.5 * eps 13 | 14 | 15 | class BCEBlurWithLogitsLoss(nn.Module): 16 | # BCEwithLogitLoss() with reduced missing label effects. 17 | def __init__(self, alpha=0.05): 18 | super(BCEBlurWithLogitsLoss, self).__init__() 19 | self.loss_fcn = nn.BCEWithLogitsLoss(reduction='none') # must be nn.BCEWithLogitsLoss() 20 | self.alpha = alpha 21 | 22 | def forward(self, pred, true): 23 | loss = self.loss_fcn(pred, true) 24 | pred = torch.sigmoid(pred) # prob from logits 25 | dx = pred - true # reduce only missing label effects 26 | # dx = (pred - true).abs() # reduce missing label and false label effects 27 | alpha_factor = 1 - torch.exp((dx - 1) / (self.alpha + 1e-4)) 28 | loss *= alpha_factor 29 | return loss.mean() 30 | 31 | 32 | class FocalLoss(nn.Module): 33 | # Wraps focal loss around existing loss_fcn(), i.e. criteria = FocalLoss(nn.BCEWithLogitsLoss(), gamma=1.5) 34 | def __init__(self, loss_fcn, gamma=1.5, alpha=0.25): 35 | super(FocalLoss, self).__init__() 36 | self.loss_fcn = loss_fcn # must be nn.BCEWithLogitsLoss() 37 | self.gamma = gamma 38 | self.alpha = alpha 39 | self.reduction = loss_fcn.reduction 40 | self.loss_fcn.reduction = 'none' # required to apply FL to each element 41 | 42 | def forward(self, pred, true): 43 | loss = self.loss_fcn(pred, true) 44 | # p_t = torch.exp(-loss) 45 | # loss *= self.alpha * (1.000001 - p_t) ** self.gamma # non-zero power for gradient stability 46 | 47 | # TF implementation https://github.com/tensorflow/addons/blob/v0.7.1/tensorflow_addons/losses/focal_loss.py 48 | pred_prob = torch.sigmoid(pred) # prob from logits 49 | p_t = true * pred_prob + (1 - true) * (1 - pred_prob) 50 | alpha_factor = true * self.alpha + (1 - true) * (1 - self.alpha) 51 | modulating_factor = (1.0 - p_t) ** self.gamma 52 | loss *= alpha_factor * modulating_factor 53 | 54 | if self.reduction == 'mean': 55 | return loss.mean() 56 | elif self.reduction == 'sum': 57 | return loss.sum() 58 | else: # 'none' 59 | return loss 60 | 61 | 62 | class QFocalLoss(nn.Module): 63 | # Wraps Quality focal loss around existing loss_fcn(), i.e. criteria = FocalLoss(nn.BCEWithLogitsLoss(), gamma=1.5) 64 | def __init__(self, loss_fcn, gamma=1.5, alpha=0.25): 65 | super(QFocalLoss, self).__init__() 66 | self.loss_fcn = loss_fcn # must be nn.BCEWithLogitsLoss() 67 | self.gamma = gamma 68 | self.alpha = alpha 69 | self.reduction = loss_fcn.reduction 70 | self.loss_fcn.reduction = 'none' # required to apply FL to each element 71 | 72 | def forward(self, pred, true): 73 | loss = self.loss_fcn(pred, true) 74 | 75 | pred_prob = torch.sigmoid(pred) # prob from logits 76 | alpha_factor = true * self.alpha + (1 - true) * (1 - self.alpha) 77 | modulating_factor = torch.abs(true - pred_prob) ** self.gamma 78 | loss *= alpha_factor * modulating_factor 79 | 80 | if self.reduction == 'mean': 81 | return loss.mean() 82 | elif self.reduction == 'sum': 83 | return loss.sum() 84 | else: # 'none' 85 | return loss 86 | 87 | 88 | class ComputeLoss: 89 | # Compute losses 90 | def __init__(self, model, autobalance=False): 91 | super(ComputeLoss, self).__init__() 92 | device = next(model.parameters()).device # get model device 93 | h = model.hyp # hyperparameters 94 | 95 | # Define criteria 96 | BCEcls = nn.BCEWithLogitsLoss(pos_weight=torch.tensor([h['cls_pw']], device=device)) 97 | BCEobj = nn.BCEWithLogitsLoss(pos_weight=torch.tensor([h['obj_pw']], device=device)) 98 | 99 | # Class label smoothing https://arxiv.org/pdf/1902.04103.pdf eqn 3 100 | self.cp, self.cn = smooth_BCE(eps=0.0) 101 | 102 | # Focal loss 103 | g = h['fl_gamma'] # focal loss gamma 104 | if g > 0: 105 | BCEcls, BCEobj = FocalLoss(BCEcls, g), FocalLoss(BCEobj, g) 106 | 107 | det = model.module.model[-1] if is_parallel(model) else model.model[-1] # Detect() module 108 | self.balance = {3: [4.0, 1.0, 0.4], 4: [4.0, 1.0, 0.25, 0.06], 5: [4.0, 1.0, 0.25, 0.06, .02]}[det.nl] 109 | self.ssi = (det.stride == 16).nonzero(as_tuple=False).item() # stride 16 index 110 | self.BCEcls, self.BCEobj, self.gr, self.hyp, self.autobalance = BCEcls, BCEobj, model.gr, h, autobalance 111 | for k in 'na', 'nc', 'nl', 'anchors': 112 | setattr(self, k, getattr(det, k)) 113 | 114 | def __call__(self, p, targets): # predictions, targets, model 115 | device = targets.device 116 | lcls, lbox, lobj = torch.zeros(1, device=device), torch.zeros(1, device=device), torch.zeros(1, device=device) 117 | tcls, tbox, indices, anchors = self.build_targets(p, targets) # targets 118 | 119 | # Losses 120 | for i, pi in enumerate(p): # layer index, layer predictions 121 | b, a, gj, gi = indices[i] # image, anchor, gridy, gridx 122 | tobj = torch.zeros_like(pi[..., 0], device=device) # target obj 123 | 124 | n = b.shape[0] # number of targets 125 | if n: 126 | ps = pi[b, a, gj, gi] # prediction subset corresponding to targets 127 | 128 | # Regression 129 | pxy = ps[:, :2].sigmoid() * 2. - 0.5 130 | pwh = (ps[:, 2:4].sigmoid() * 2) ** 2 * anchors[i] 131 | pbox = torch.cat((pxy, pwh), 1) # predicted box 132 | iou = bbox_iou(pbox.T, tbox[i], x1y1x2y2=False, CIoU=True) # iou(prediction, target) 133 | lbox += (1.0 - iou).mean() # iou loss 134 | 135 | # Objectness 136 | tobj[b, a, gj, gi] = (1.0 - self.gr) + self.gr * iou.detach().clamp(0).type(tobj.dtype) # iou ratio 137 | 138 | # Classification 139 | if self.nc > 1: # cls loss (only if multiple classes) 140 | t = torch.full_like(ps[:, 5:], self.cn, device=device) # targets 141 | t[range(n), tcls[i]] = self.cp 142 | lcls += self.BCEcls(ps[:, 5:], t) # BCE 143 | 144 | # Append targets to text file 145 | # with open('targets.txt', 'a') as file: 146 | # [file.write('%11.5g ' * 4 % tuple(x) + '\n') for x in torch.cat((txy[i], twh[i]), 1)] 147 | 148 | obji = self.BCEobj(pi[..., 4], tobj) 149 | lobj += obji * self.balance[i] # obj loss 150 | if self.autobalance: 151 | self.balance[i] = self.balance[i] * 0.9999 + 0.0001 / obji.detach().item() 152 | 153 | if self.autobalance: 154 | self.balance = [x / self.balance[self.ssi] for x in self.balance] 155 | lbox *= self.hyp['box'] 156 | lobj *= self.hyp['obj'] 157 | lcls *= self.hyp['cls'] 158 | bs = tobj.shape[0] # batch size 159 | 160 | loss = lbox + lobj + lcls 161 | return loss * bs, torch.cat((lbox, lobj, lcls, loss)).detach() 162 | 163 | def build_targets(self, p, targets): 164 | # Build targets for compute_loss(), input targets(image,class,x,y,w,h) 165 | na, nt = self.na, targets.shape[0] # number of anchors, targets 166 | tcls, tbox, indices, anch = [], [], [], [] 167 | gain = torch.ones(7, device=targets.device) # normalized to gridspace gain 168 | ai = torch.arange(na, device=targets.device).float().view(na, 1).repeat(1, nt) # same as .repeat_interleave(nt) 169 | targets = torch.cat((targets.repeat(na, 1, 1), ai[:, :, None]), 2) # append anchor indices 170 | 171 | g = 0.5 # bias 172 | off = torch.tensor([[0, 0], 173 | [1, 0], [0, 1], [-1, 0], [0, -1], # j,k,l,m 174 | # [1, 1], [1, -1], [-1, 1], [-1, -1], # jk,jm,lk,lm 175 | ], device=targets.device).float() * g # offsets 176 | 177 | for i in range(self.nl): 178 | anchors = self.anchors[i] 179 | gain[2:6] = torch.tensor(p[i].shape)[[3, 2, 3, 2]] # xyxy gain 180 | 181 | # Match targets to anchors 182 | t = targets * gain 183 | if nt: 184 | # Matches 185 | r = t[:, :, 4:6] / anchors[:, None] # wh ratio 186 | j = torch.max(r, 1. / r).max(2)[0] < self.hyp['anchor_t'] # compare 187 | # j = wh_iou(anchors, t[:, 4:6]) > model.hyp['iou_t'] # iou(3,n)=wh_iou(anchors(3,2), gwh(n,2)) 188 | t = t[j] # filter 189 | 190 | # Offsets 191 | gxy = t[:, 2:4] # grid xy 192 | gxi = gain[[2, 3]] - gxy # inverse 193 | j, k = ((gxy % 1. < g) & (gxy > 1.)).T 194 | l, m = ((gxi % 1. < g) & (gxi > 1.)).T 195 | j = torch.stack((torch.ones_like(j), j, k, l, m)) 196 | t = t.repeat((5, 1, 1))[j] 197 | offsets = (torch.zeros_like(gxy)[None] + off[:, None])[j] 198 | else: 199 | t = targets[0] 200 | offsets = 0 201 | 202 | # Define 203 | b, c = t[:, :2].long().T # image, class 204 | gxy = t[:, 2:4] # grid xy 205 | gwh = t[:, 4:6] # grid wh 206 | gij = (gxy - offsets).long() 207 | gi, gj = gij.T # grid xy indices 208 | 209 | # Append 210 | a = t[:, 6].long() # anchor indices 211 | indices.append((b, a, gj.clamp_(0, gain[3] - 1), gi.clamp_(0, gain[2] - 1))) # image, anchor, grid indices 212 | tbox.append(torch.cat((gxy - gij, gwh), 1)) # box 213 | anch.append(anchors[a]) # anchors 214 | tcls.append(c) # class 215 | 216 | return tcls, tbox, indices, anch 217 | -------------------------------------------------------------------------------- /src/utils/metrics.py: -------------------------------------------------------------------------------- 1 | # Model validation metrics 2 | 3 | from pathlib import Path 4 | 5 | import matplotlib.pyplot as plt 6 | import numpy as np 7 | import torch 8 | 9 | from . import general 10 | 11 | 12 | def fitness(x): 13 | # Model fitness as a weighted combination of metrics 14 | w = [0.0, 0.0, 0.1, 0.9] # weights for [P, R, mAP@0.5, mAP@0.5:0.95] 15 | return (x[:, :4] * w).sum(1) 16 | 17 | 18 | def ap_per_class(tp, conf, pred_cls, target_cls, plot=False, save_dir='.', names=()): 19 | """ Compute the average precision, given the recall and precision curves. 20 | Source: https://github.com/rafaelpadilla/Object-Detection-Metrics. 21 | # Arguments 22 | tp: True positives (nparray, nx1 or nx10). 23 | conf: Objectness value from 0-1 (nparray). 24 | pred_cls: Predicted object classes (nparray). 25 | target_cls: True object classes (nparray). 26 | plot: Plot precision-recall curve at mAP@0.5 27 | save_dir: Plot save directory 28 | # Returns 29 | The average precision as computed in py-faster-rcnn. 30 | """ 31 | 32 | # Sort by objectness 33 | i = np.argsort(-conf) 34 | tp, conf, pred_cls = tp[i], conf[i], pred_cls[i] 35 | 36 | # Find unique classes 37 | unique_classes = np.unique(target_cls) 38 | nc = unique_classes.shape[0] # number of classes, number of detections 39 | 40 | # Create Precision-Recall curve and compute AP for each class 41 | px, py = np.linspace(0, 1, 1000), [] # for plotting 42 | ap, p, r = np.zeros((nc, tp.shape[1])), np.zeros((nc, 1000)), np.zeros((nc, 1000)) 43 | for ci, c in enumerate(unique_classes): 44 | i = pred_cls == c 45 | n_l = (target_cls == c).sum() # number of labels 46 | n_p = i.sum() # number of predictions 47 | 48 | if n_p == 0 or n_l == 0: 49 | continue 50 | else: 51 | # Accumulate FPs and TPs 52 | fpc = (1 - tp[i]).cumsum(0) 53 | tpc = tp[i].cumsum(0) 54 | 55 | # Recall 56 | recall = tpc / (n_l + 1e-16) # recall curve 57 | r[ci] = np.interp(-px, -conf[i], recall[:, 0], left=0) # negative x, xp because xp decreases 58 | 59 | # Precision 60 | precision = tpc / (tpc + fpc) # precision curve 61 | p[ci] = np.interp(-px, -conf[i], precision[:, 0], left=1) # p at pr_score 62 | 63 | # AP from recall-precision curve 64 | for j in range(tp.shape[1]): 65 | ap[ci, j], mpre, mrec = compute_ap(recall[:, j], precision[:, j]) 66 | if plot and j == 0: 67 | py.append(np.interp(px, mrec, mpre)) # precision at mAP@0.5 68 | 69 | # Compute F1 (harmonic mean of precision and recall) 70 | f1 = 2 * p * r / (p + r + 1e-16) 71 | if plot: 72 | plot_pr_curve(px, py, ap, Path(save_dir) / 'PR_curve.png', names) 73 | plot_mc_curve(px, f1, Path(save_dir) / 'F1_curve.png', names, ylabel='F1') 74 | plot_mc_curve(px, p, Path(save_dir) / 'P_curve.png', names, ylabel='Precision') 75 | plot_mc_curve(px, r, Path(save_dir) / 'R_curve.png', names, ylabel='Recall') 76 | 77 | i = f1.mean(0).argmax() # max F1 index 78 | return p[:, i], r[:, i], ap, f1[:, i], unique_classes.astype('int32') 79 | 80 | 81 | def compute_ap(recall, precision): 82 | """ Compute the average precision, given the recall and precision curves 83 | # Arguments 84 | recall: The recall curve (list) 85 | precision: The precision curve (list) 86 | # Returns 87 | Average precision, precision curve, recall curve 88 | """ 89 | 90 | # Append sentinel values to beginning and end 91 | mrec = np.concatenate(([0.], recall, [recall[-1] + 0.01])) 92 | mpre = np.concatenate(([1.], precision, [0.])) 93 | 94 | # Compute the precision envelope 95 | mpre = np.flip(np.maximum.accumulate(np.flip(mpre))) 96 | 97 | # Integrate area under curve 98 | method = 'interp' # methods: 'continuous', 'interp' 99 | if method == 'interp': 100 | x = np.linspace(0, 1, 101) # 101-point interp (COCO) 101 | ap = np.trapz(np.interp(x, mrec, mpre), x) # integrate 102 | else: # 'continuous' 103 | i = np.where(mrec[1:] != mrec[:-1])[0] # points where x axis (recall) changes 104 | ap = np.sum((mrec[i + 1] - mrec[i]) * mpre[i + 1]) # area under curve 105 | 106 | return ap, mpre, mrec 107 | 108 | 109 | class ConfusionMatrix: 110 | # Updated version of https://github.com/kaanakan/object_detection_confusion_matrix 111 | def __init__(self, nc, conf=0.25, iou_thres=0.45): 112 | self.matrix = np.zeros((nc + 1, nc + 1)) 113 | self.nc = nc # number of classes 114 | self.conf = conf 115 | self.iou_thres = iou_thres 116 | 117 | def process_batch(self, detections, labels): 118 | """ 119 | Return intersection-over-union (Jaccard index) of boxes. 120 | Both sets of boxes are expected to be in (x1, y1, x2, y2) format. 121 | Arguments: 122 | detections (Array[N, 6]), x1, y1, x2, y2, conf, class 123 | labels (Array[M, 5]), class, x1, y1, x2, y2 124 | Returns: 125 | None, updates confusion matrix accordingly 126 | """ 127 | detections = detections[detections[:, 4] > self.conf] 128 | gt_classes = labels[:, 0].int() 129 | detection_classes = detections[:, 5].int() 130 | iou = general.box_iou(labels[:, 1:], detections[:, :4]) 131 | 132 | x = torch.where(iou > self.iou_thres) 133 | if x[0].shape[0]: 134 | matches = torch.cat((torch.stack(x, 1), iou[x[0], x[1]][:, None]), 1).cpu().numpy() 135 | if x[0].shape[0] > 1: 136 | matches = matches[matches[:, 2].argsort()[::-1]] 137 | matches = matches[np.unique(matches[:, 1], return_index=True)[1]] 138 | matches = matches[matches[:, 2].argsort()[::-1]] 139 | matches = matches[np.unique(matches[:, 0], return_index=True)[1]] 140 | else: 141 | matches = np.zeros((0, 3)) 142 | 143 | n = matches.shape[0] > 0 144 | m0, m1, _ = matches.transpose().astype(np.int16) 145 | for i, gc in enumerate(gt_classes): 146 | j = m0 == i 147 | if n and sum(j) == 1: 148 | self.matrix[gc, detection_classes[m1[j]]] += 1 # correct 149 | else: 150 | self.matrix[gc, self.nc] += 1 # background FP 151 | 152 | if n: 153 | for i, dc in enumerate(detection_classes): 154 | if not any(m1 == i): 155 | self.matrix[self.nc, dc] += 1 # background FN 156 | 157 | def matrix(self): 158 | return self.matrix 159 | 160 | def plot(self, save_dir='', names=()): 161 | try: 162 | import seaborn as sn 163 | 164 | array = self.matrix / (self.matrix.sum(0).reshape(1, self.nc + 1) + 1E-6) # normalize 165 | array[array < 0.005] = np.nan # don't annotate (would appear as 0.00) 166 | 167 | fig = plt.figure(figsize=(12, 9), tight_layout=True) 168 | sn.set(font_scale=1.0 if self.nc < 50 else 0.8) # for label size 169 | labels = (0 < len(names) < 99) and len(names) == self.nc # apply names to ticklabels 170 | sn.heatmap(array, annot=self.nc < 30, annot_kws={"size": 8}, cmap='Blues', fmt='.2f', square=True, 171 | xticklabels=names + ['background FN'] if labels else "auto", 172 | yticklabels=names + ['background FP'] if labels else "auto").set_facecolor((1, 1, 1)) 173 | fig.axes[0].set_xlabel('True') 174 | fig.axes[0].set_ylabel('Predicted') 175 | fig.savefig(Path(save_dir) / 'confusion_matrix.png', dpi=250) 176 | except Exception as e: 177 | pass 178 | 179 | def print(self): 180 | for i in range(self.nc + 1): 181 | print(' '.join(map(str, self.matrix[i]))) 182 | 183 | 184 | # Plots ---------------------------------------------------------------------------------------------------------------- 185 | 186 | def plot_pr_curve(px, py, ap, save_dir='pr_curve.png', names=()): 187 | # Precision-recall curve 188 | fig, ax = plt.subplots(1, 1, figsize=(9, 6), tight_layout=True) 189 | py = np.stack(py, axis=1) 190 | 191 | if 0 < len(names) < 21: # display per-class legend if < 21 classes 192 | for i, y in enumerate(py.T): 193 | ax.plot(px, y, linewidth=1, label=f'{names[i]} {ap[i, 0]:.3f}') # plot(recall, precision) 194 | else: 195 | ax.plot(px, py, linewidth=1, color='grey') # plot(recall, precision) 196 | 197 | ax.plot(px, py.mean(1), linewidth=3, color='blue', label='all classes %.3f mAP@0.5' % ap[:, 0].mean()) 198 | ax.set_xlabel('Recall') 199 | ax.set_ylabel('Precision') 200 | ax.set_xlim(0, 1) 201 | ax.set_ylim(0, 1) 202 | plt.legend(bbox_to_anchor=(1.04, 1), loc="upper left") 203 | fig.savefig(Path(save_dir), dpi=250) 204 | 205 | 206 | def plot_mc_curve(px, py, save_dir='mc_curve.png', names=(), xlabel='Confidence', ylabel='Metric'): 207 | # Metric-confidence curve 208 | fig, ax = plt.subplots(1, 1, figsize=(9, 6), tight_layout=True) 209 | 210 | if 0 < len(names) < 21: # display per-class legend if < 21 classes 211 | for i, y in enumerate(py): 212 | ax.plot(px, y, linewidth=1, label=f'{names[i]}') # plot(confidence, metric) 213 | else: 214 | ax.plot(px, py.T, linewidth=1, color='grey') # plot(confidence, metric) 215 | 216 | y = py.mean(0) 217 | ax.plot(px, y, linewidth=3, color='blue', label=f'all classes {y.max():.2f} at {px[y.argmax()]:.3f}') 218 | ax.set_xlabel(xlabel) 219 | ax.set_ylabel(ylabel) 220 | ax.set_xlim(0, 1) 221 | ax.set_ylim(0, 1) 222 | plt.legend(bbox_to_anchor=(1.04, 1), loc="upper left") 223 | fig.savefig(Path(save_dir), dpi=250) 224 | -------------------------------------------------------------------------------- /src/utils/plots.py: -------------------------------------------------------------------------------- 1 | # Plotting utils 2 | 3 | import glob 4 | import math 5 | import os 6 | import random 7 | from copy import copy 8 | from pathlib import Path 9 | 10 | import cv2 11 | import matplotlib 12 | import matplotlib.pyplot as plt 13 | import numpy as np 14 | import pandas as pd 15 | import seaborn as sns 16 | import torch 17 | import yaml 18 | from PIL import Image, ImageDraw 19 | from scipy.signal import butter, filtfilt 20 | 21 | from utils.general import xywh2xyxy, xyxy2xywh 22 | from utils.metrics import fitness 23 | 24 | # Settings 25 | matplotlib.rc('font', **{'size': 11}) 26 | matplotlib.use('Agg') # for writing to files only 27 | 28 | 29 | def color_list(): 30 | # Return first 10 plt colors as (r,g,b) https://stackoverflow.com/questions/51350872/python-from-color-name-to-rgb 31 | def hex2rgb(h): 32 | return tuple(int(h[1 + i:1 + i + 2], 16) for i in (0, 2, 4)) 33 | 34 | return [hex2rgb(h) for h in matplotlib.colors.TABLEAU_COLORS.values()] # or BASE_ (8), CSS4_ (148), XKCD_ (949) 35 | 36 | 37 | def hist2d(x, y, n=100): 38 | # 2d histogram used in labels.png and evolve.png 39 | xedges, yedges = np.linspace(x.min(), x.max(), n), np.linspace(y.min(), y.max(), n) 40 | hist, xedges, yedges = np.histogram2d(x, y, (xedges, yedges)) 41 | xidx = np.clip(np.digitize(x, xedges) - 1, 0, hist.shape[0] - 1) 42 | yidx = np.clip(np.digitize(y, yedges) - 1, 0, hist.shape[1] - 1) 43 | return np.log(hist[xidx, yidx]) 44 | 45 | 46 | def butter_lowpass_filtfilt(data, cutoff=1500, fs=50000, order=5): 47 | # https://stackoverflow.com/questions/28536191/how-to-filter-smooth-with-scipy-numpy 48 | def butter_lowpass(cutoff, fs, order): 49 | nyq = 0.5 * fs 50 | normal_cutoff = cutoff / nyq 51 | return butter(order, normal_cutoff, btype='low', analog=False) 52 | 53 | b, a = butter_lowpass(cutoff, fs, order=order) 54 | return filtfilt(b, a, data) # forward-backward filter 55 | 56 | 57 | def plot_one_box(x, img, color=None, label=None, line_thickness=None): 58 | # Plots one bounding box on image img 59 | tl = line_thickness or round(0.002 * (img.shape[0] + img.shape[1]) / 2) + 1 # line/font thickness 60 | color = color or [random.randint(0, 255) for _ in range(3)] 61 | c1, c2 = (int(x[0]), int(x[1])), (int(x[2]), int(x[3])) 62 | cv2.rectangle(img, c1, c2, color, thickness=tl, lineType=cv2.LINE_AA) 63 | if label: 64 | tf = max(tl - 1, 1) # font thickness 65 | t_size = cv2.getTextSize(label, 0, fontScale=tl / 3, thickness=tf)[0] 66 | c2 = c1[0] + t_size[0], c1[1] - t_size[1] - 3 67 | cv2.rectangle(img, c1, c2, color, -1, cv2.LINE_AA) # filled 68 | cv2.putText(img, label, (c1[0], c1[1] - 2), 0, tl / 3, [225, 255, 255], thickness=tf, lineType=cv2.LINE_AA) 69 | 70 | 71 | def plot_wh_methods(): # from utils.plots import *; plot_wh_methods() 72 | # Compares the two methods for width-height anchor multiplication 73 | # https://github.com/ultralytics/yolov3/issues/168 74 | x = np.arange(-4.0, 4.0, .1) 75 | ya = np.exp(x) 76 | yb = torch.sigmoid(torch.from_numpy(x)).numpy() * 2 77 | 78 | fig = plt.figure(figsize=(6, 3), tight_layout=True) 79 | plt.plot(x, ya, '.-', label='YOLOv3') 80 | plt.plot(x, yb ** 2, '.-', label='YOLOv5 ^2') 81 | plt.plot(x, yb ** 1.6, '.-', label='YOLOv5 ^1.6') 82 | plt.xlim(left=-4, right=4) 83 | plt.ylim(bottom=0, top=6) 84 | plt.xlabel('input') 85 | plt.ylabel('output') 86 | plt.grid() 87 | plt.legend() 88 | fig.savefig('comparison.png', dpi=200) 89 | 90 | 91 | def output_to_target(output): 92 | # Convert model output to target format [batch_id, class_id, x, y, w, h, conf] 93 | targets = [] 94 | for i, o in enumerate(output): 95 | for *box, conf, cls in o.cpu().numpy(): 96 | targets.append([i, cls, *list(*xyxy2xywh(np.array(box)[None])), conf]) 97 | return np.array(targets) 98 | 99 | 100 | def plot_images(images, targets, paths=None, fname='images.jpg', names=None, max_size=640, max_subplots=16): 101 | # Plot image grid with labels 102 | 103 | if isinstance(images, torch.Tensor): 104 | images = images.cpu().float().numpy() 105 | if isinstance(targets, torch.Tensor): 106 | targets = targets.cpu().numpy() 107 | 108 | # un-normalise 109 | if np.max(images[0]) <= 1: 110 | images *= 255 111 | 112 | tl = 3 # line thickness 113 | tf = max(tl - 1, 1) # font thickness 114 | bs, _, h, w = images.shape # batch size, _, height, width 115 | bs = min(bs, max_subplots) # limit plot images 116 | ns = np.ceil(bs ** 0.5) # number of subplots (square) 117 | 118 | # Check if we should resize 119 | scale_factor = max_size / max(h, w) 120 | if scale_factor < 1: 121 | h = math.ceil(scale_factor * h) 122 | w = math.ceil(scale_factor * w) 123 | 124 | colors = color_list() # list of colors 125 | mosaic = np.full((int(ns * h), int(ns * w), 3), 255, dtype=np.uint8) # init 126 | for i, img in enumerate(images): 127 | if i == max_subplots: # if last batch has fewer images than we expect 128 | break 129 | 130 | block_x = int(w * (i // ns)) 131 | block_y = int(h * (i % ns)) 132 | 133 | img = img.transpose(1, 2, 0) 134 | if scale_factor < 1: 135 | img = cv2.resize(img, (w, h)) 136 | 137 | mosaic[block_y:block_y + h, block_x:block_x + w, :] = img 138 | if len(targets) > 0: 139 | image_targets = targets[targets[:, 0] == i] 140 | boxes = xywh2xyxy(image_targets[:, 2:6]).T 141 | classes = image_targets[:, 1].astype('int') 142 | labels = image_targets.shape[1] == 6 # labels if no conf column 143 | conf = None if labels else image_targets[:, 6] # check for confidence presence (label vs pred) 144 | 145 | if boxes.shape[1]: 146 | if boxes.max() <= 1.01: # if normalized with tolerance 0.01 147 | boxes[[0, 2]] *= w # scale to pixels 148 | boxes[[1, 3]] *= h 149 | elif scale_factor < 1: # absolute coords need scale if image scales 150 | boxes *= scale_factor 151 | boxes[[0, 2]] += block_x 152 | boxes[[1, 3]] += block_y 153 | for j, box in enumerate(boxes.T): 154 | cls = int(classes[j]) 155 | color = colors[cls % len(colors)] 156 | cls = names[cls] if names else cls 157 | if labels or conf[j] > 0.25: # 0.25 conf thresh 158 | label = '%s' % cls if labels else '%s %.1f' % (cls, conf[j]) 159 | plot_one_box(box, mosaic, label=label, color=color, line_thickness=tl) 160 | 161 | # Draw image filename labels 162 | if paths: 163 | label = Path(paths[i]).name[:40] # trim to 40 char 164 | t_size = cv2.getTextSize(label, 0, fontScale=tl / 3, thickness=tf)[0] 165 | cv2.putText(mosaic, label, (block_x + 5, block_y + t_size[1] + 5), 0, tl / 3, [220, 220, 220], thickness=tf, 166 | lineType=cv2.LINE_AA) 167 | 168 | # Image border 169 | cv2.rectangle(mosaic, (block_x, block_y), (block_x + w, block_y + h), (255, 255, 255), thickness=3) 170 | 171 | if fname: 172 | r = min(1280. / max(h, w) / ns, 1.0) # ratio to limit image size 173 | mosaic = cv2.resize(mosaic, (int(ns * w * r), int(ns * h * r)), interpolation=cv2.INTER_AREA) 174 | # cv2.imwrite(fname, cv2.cvtColor(mosaic, cv2.COLOR_BGR2RGB)) # cv2 save 175 | Image.fromarray(mosaic).save(fname) # PIL save 176 | return mosaic 177 | 178 | 179 | def plot_lr_scheduler(optimizer, scheduler, epochs=300, save_dir=''): 180 | # Plot LR simulating training for full epochs 181 | optimizer, scheduler = copy(optimizer), copy(scheduler) # do not modify originals 182 | y = [] 183 | for _ in range(epochs): 184 | scheduler.step() 185 | y.append(optimizer.param_groups[0]['lr']) 186 | plt.plot(y, '.-', label='LR') 187 | plt.xlabel('epoch') 188 | plt.ylabel('LR') 189 | plt.grid() 190 | plt.xlim(0, epochs) 191 | plt.ylim(0) 192 | plt.savefig(Path(save_dir) / 'LR.png', dpi=200) 193 | plt.close() 194 | 195 | 196 | def plot_test_txt(): # from utils.plots import *; plot_test() 197 | # Plot test.txt histograms 198 | x = np.loadtxt('test.txt', dtype=np.float32) 199 | box = xyxy2xywh(x[:, :4]) 200 | cx, cy = box[:, 0], box[:, 1] 201 | 202 | fig, ax = plt.subplots(1, 1, figsize=(6, 6), tight_layout=True) 203 | ax.hist2d(cx, cy, bins=600, cmax=10, cmin=0) 204 | ax.set_aspect('equal') 205 | plt.savefig('hist2d.png', dpi=300) 206 | 207 | fig, ax = plt.subplots(1, 2, figsize=(12, 6), tight_layout=True) 208 | ax[0].hist(cx, bins=600) 209 | ax[1].hist(cy, bins=600) 210 | plt.savefig('hist1d.png', dpi=200) 211 | 212 | 213 | def plot_targets_txt(): # from utils.plots import *; plot_targets_txt() 214 | # Plot targets.txt histograms 215 | x = np.loadtxt('targets.txt', dtype=np.float32).T 216 | s = ['x targets', 'y targets', 'width targets', 'height targets'] 217 | fig, ax = plt.subplots(2, 2, figsize=(8, 8), tight_layout=True) 218 | ax = ax.ravel() 219 | for i in range(4): 220 | ax[i].hist(x[i], bins=100, label='%.3g +/- %.3g' % (x[i].mean(), x[i].std())) 221 | ax[i].legend() 222 | ax[i].set_title(s[i]) 223 | plt.savefig('targets.jpg', dpi=200) 224 | 225 | 226 | def plot_study_txt(path='', x=None): # from utils.plots import *; plot_study_txt() 227 | # Plot study.txt generated by test.py 228 | fig, ax = plt.subplots(2, 4, figsize=(10, 6), tight_layout=True) 229 | # ax = ax.ravel() 230 | 231 | fig2, ax2 = plt.subplots(1, 1, figsize=(8, 4), tight_layout=True) 232 | # for f in [Path(path) / f'study_coco_{x}.txt' for x in ['yolov5s', 'yolov5m', 'yolov5l', 'yolov5x']]: 233 | for f in sorted(Path(path).glob('study*.txt')): 234 | y = np.loadtxt(f, dtype=np.float32, usecols=[0, 1, 2, 3, 7, 8, 9], ndmin=2).T 235 | x = np.arange(y.shape[1]) if x is None else np.array(x) 236 | s = ['P', 'R', 'mAP@.5', 'mAP@.5:.95', 't_inference (ms/img)', 't_NMS (ms/img)', 't_total (ms/img)'] 237 | # for i in range(7): 238 | # ax[i].plot(x, y[i], '.-', linewidth=2, markersize=8) 239 | # ax[i].set_title(s[i]) 240 | 241 | j = y[3].argmax() + 1 242 | ax2.plot(y[6, :j], y[3, :j] * 1E2, '.-', linewidth=2, markersize=8, 243 | label=f.stem.replace('study_coco_', '').replace('yolo', 'YOLO')) 244 | 245 | ax2.plot(1E3 / np.array([209, 140, 97, 58, 35, 18]), [34.6, 40.5, 43.0, 47.5, 49.7, 51.5], 246 | 'k.-', linewidth=2, markersize=8, alpha=.25, label='EfficientDet') 247 | 248 | ax2.grid(alpha=0.2) 249 | ax2.set_yticks(np.arange(20, 60, 5)) 250 | ax2.set_xlim(0, 30) 251 | ax2.set_ylim(30, 55) 252 | ax2.set_xlabel('GPU Speed (ms/img)') 253 | ax2.set_ylabel('COCO AP val') 254 | ax2.legend(loc='lower right') 255 | plt.savefig(str(Path(path).name) + '.png', dpi=300) 256 | 257 | 258 | def plot_labels(labels, save_dir=Path(''), loggers=None): 259 | # plot dataset labels 260 | print('Plotting labels... ') 261 | c, b = labels[:, 0], labels[:, 1:].transpose() # classes, boxes 262 | nc = int(c.max() + 1) # number of classes 263 | colors = color_list() 264 | x = pd.DataFrame(b.transpose(), columns=['x', 'y', 'width', 'height']) 265 | 266 | # seaborn correlogram 267 | sns.pairplot(x, corner=True, diag_kind='auto', kind='hist', diag_kws=dict(bins=50), plot_kws=dict(pmax=0.9)) 268 | plt.savefig(save_dir / 'labels_correlogram.jpg', dpi=200) 269 | plt.close() 270 | 271 | # matplotlib labels 272 | matplotlib.use('svg') # faster 273 | ax = plt.subplots(2, 2, figsize=(8, 8), tight_layout=True)[1].ravel() 274 | ax[0].hist(c, bins=np.linspace(0, nc, nc + 1) - 0.5, rwidth=0.8) 275 | ax[0].set_xlabel('classes') 276 | sns.histplot(x, x='x', y='y', ax=ax[2], bins=50, pmax=0.9) 277 | sns.histplot(x, x='width', y='height', ax=ax[3], bins=50, pmax=0.9) 278 | 279 | # rectangles 280 | labels[:, 1:3] = 0.5 # center 281 | labels[:, 1:] = xywh2xyxy(labels[:, 1:]) * 2000 282 | img = Image.fromarray(np.ones((2000, 2000, 3), dtype=np.uint8) * 255) 283 | for cls, *box in labels[:1000]: 284 | ImageDraw.Draw(img).rectangle(box, width=1, outline=colors[int(cls) % 10]) # plot 285 | ax[1].imshow(img) 286 | ax[1].axis('off') 287 | 288 | for a in [0, 1, 2, 3]: 289 | for s in ['top', 'right', 'left', 'bottom']: 290 | ax[a].spines[s].set_visible(False) 291 | 292 | plt.savefig(save_dir / 'labels.jpg', dpi=200) 293 | matplotlib.use('Agg') 294 | plt.close() 295 | 296 | # loggers 297 | for k, v in loggers.items() or {}: 298 | if k == 'wandb' and v: 299 | v.log({"Labels": [v.Image(str(x), caption=x.name) for x in save_dir.glob('*labels*.jpg')]}, commit=False) 300 | 301 | 302 | def plot_evolution(yaml_file='data/hyp.finetune.yaml'): # from utils.plots import *; plot_evolution() 303 | # Plot hyperparameter evolution results in evolve.txt 304 | with open(yaml_file) as f: 305 | hyp = yaml.load(f, Loader=yaml.SafeLoader) 306 | x = np.loadtxt('evolve.txt', ndmin=2) 307 | f = fitness(x) 308 | # weights = (f - f.min()) ** 2 # for weighted results 309 | plt.figure(figsize=(10, 12), tight_layout=True) 310 | matplotlib.rc('font', **{'size': 8}) 311 | for i, (k, v) in enumerate(hyp.items()): 312 | y = x[:, i + 7] 313 | # mu = (y * weights).sum() / weights.sum() # best weighted result 314 | mu = y[f.argmax()] # best single result 315 | plt.subplot(6, 5, i + 1) 316 | plt.scatter(y, f, c=hist2d(y, f, 20), cmap='viridis', alpha=.8, edgecolors='none') 317 | plt.plot(mu, f.max(), 'k+', markersize=15) 318 | plt.title('%s = %.3g' % (k, mu), fontdict={'size': 9}) # limit to 40 characters 319 | if i % 5 != 0: 320 | plt.yticks([]) 321 | print('%15s: %.3g' % (k, mu)) 322 | plt.savefig('evolve.png', dpi=200) 323 | print('\nPlot saved as evolve.png') 324 | 325 | 326 | def profile_idetection(start=0, stop=0, labels=(), save_dir=''): 327 | # Plot iDetection '*.txt' per-image logs. from utils.plots import *; profile_idetection() 328 | ax = plt.subplots(2, 4, figsize=(12, 6), tight_layout=True)[1].ravel() 329 | s = ['Images', 'Free Storage (GB)', 'RAM Usage (GB)', 'Battery', 'dt_raw (ms)', 'dt_smooth (ms)', 'real-world FPS'] 330 | files = list(Path(save_dir).glob('frames*.txt')) 331 | for fi, f in enumerate(files): 332 | try: 333 | results = np.loadtxt(f, ndmin=2).T[:, 90:-30] # clip first and last rows 334 | n = results.shape[1] # number of rows 335 | x = np.arange(start, min(stop, n) if stop else n) 336 | results = results[:, x] 337 | t = (results[0] - results[0].min()) # set t0=0s 338 | results[0] = x 339 | for i, a in enumerate(ax): 340 | if i < len(results): 341 | label = labels[fi] if len(labels) else f.stem.replace('frames_', '') 342 | a.plot(t, results[i], marker='.', label=label, linewidth=1, markersize=5) 343 | a.set_title(s[i]) 344 | a.set_xlabel('time (s)') 345 | # if fi == len(files) - 1: 346 | # a.set_ylim(bottom=0) 347 | for side in ['top', 'right']: 348 | a.spines[side].set_visible(False) 349 | else: 350 | a.remove() 351 | except Exception as e: 352 | print('Warning: Plotting error for %s; %s' % (f, e)) 353 | 354 | ax[1].legend() 355 | plt.savefig(Path(save_dir) / 'idetection_profile.png', dpi=200) 356 | 357 | 358 | def plot_results_overlay(start=0, stop=0): # from utils.plots import *; plot_results_overlay() 359 | # Plot training 'results*.txt', overlaying train and val losses 360 | s = ['train', 'train', 'train', 'Precision', 'mAP@0.5', 'val', 'val', 'val', 'Recall', 'mAP@0.5:0.95'] # legends 361 | t = ['Box', 'Objectness', 'Classification', 'P-R', 'mAP-F1'] # titles 362 | for f in sorted(glob.glob('results*.txt') + glob.glob('../../Downloads/results*.txt')): 363 | results = np.loadtxt(f, usecols=[2, 3, 4, 8, 9, 12, 13, 14, 10, 11], ndmin=2).T 364 | n = results.shape[1] # number of rows 365 | x = range(start, min(stop, n) if stop else n) 366 | fig, ax = plt.subplots(1, 5, figsize=(14, 3.5), tight_layout=True) 367 | ax = ax.ravel() 368 | for i in range(5): 369 | for j in [i, i + 5]: 370 | y = results[j, x] 371 | ax[i].plot(x, y, marker='.', label=s[j]) 372 | # y_smooth = butter_lowpass_filtfilt(y) 373 | # ax[i].plot(x, np.gradient(y_smooth), marker='.', label=s[j]) 374 | 375 | ax[i].set_title(t[i]) 376 | ax[i].legend() 377 | ax[i].set_ylabel(f) if i == 0 else None # add filename 378 | fig.savefig(f.replace('.txt', '.png'), dpi=200) 379 | 380 | 381 | def plot_results(start=0, stop=0, bucket='', id=(), labels=(), save_dir=''): 382 | # Plot training 'results*.txt'. from utils.plots import *; plot_results(save_dir='runs/train/exp') 383 | fig, ax = plt.subplots(2, 5, figsize=(12, 6), tight_layout=True) 384 | ax = ax.ravel() 385 | s = ['Box', 'Objectness', 'Classification', 'Precision', 'Recall', 386 | 'val Box', 'val Objectness', 'val Classification', 'mAP@0.5', 'mAP@0.5:0.95'] 387 | if bucket: 388 | # files = ['https://storage.googleapis.com/%s/results%g.txt' % (bucket, x) for x in id] 389 | files = ['results%g.txt' % x for x in id] 390 | c = ('gsutil cp ' + '%s ' * len(files) + '.') % tuple('gs://%s/results%g.txt' % (bucket, x) for x in id) 391 | os.system(c) 392 | else: 393 | files = list(Path(save_dir).glob('results*.txt')) 394 | assert len(files), 'No results.txt files found in %s, nothing to plot.' % os.path.abspath(save_dir) 395 | for fi, f in enumerate(files): 396 | try: 397 | results = np.loadtxt(f, usecols=[2, 3, 4, 8, 9, 12, 13, 14, 10, 11], ndmin=2).T 398 | n = results.shape[1] # number of rows 399 | x = range(start, min(stop, n) if stop else n) 400 | for i in range(10): 401 | y = results[i, x] 402 | if i in [0, 1, 2, 5, 6, 7]: 403 | y[y == 0] = np.nan # don't show zero loss values 404 | # y /= y[0] # normalize 405 | label = labels[fi] if len(labels) else f.stem 406 | ax[i].plot(x, y, marker='.', label=label, linewidth=2, markersize=8) 407 | ax[i].set_title(s[i]) 408 | # if i in [5, 6, 7]: # share train and val loss y axes 409 | # ax[i].get_shared_y_axes().join(ax[i], ax[i - 5]) 410 | except Exception as e: 411 | print('Warning: Plotting error for %s; %s' % (f, e)) 412 | 413 | ax[1].legend() 414 | fig.savefig(Path(save_dir) / 'results.png', dpi=200) 415 | -------------------------------------------------------------------------------- /src/utils/torch_utils.py: -------------------------------------------------------------------------------- 1 | # PyTorch utils 2 | 3 | import logging 4 | import math 5 | import os 6 | import subprocess 7 | import time 8 | from contextlib import contextmanager 9 | from copy import deepcopy 10 | from pathlib import Path 11 | 12 | import torch 13 | import torch.backends.cudnn as cudnn 14 | import torch.nn as nn 15 | import torch.nn.functional as F 16 | import torchvision 17 | 18 | try: 19 | import thop # for FLOPS computation 20 | except ImportError: 21 | thop = None 22 | logger = logging.getLogger(__name__) 23 | 24 | 25 | @contextmanager 26 | def torch_distributed_zero_first(local_rank: int): 27 | """ 28 | Decorator to make all processes in distributed training wait for each local_master to do something. 29 | """ 30 | if local_rank not in [-1, 0]: 31 | torch.distributed.barrier() 32 | yield 33 | if local_rank == 0: 34 | torch.distributed.barrier() 35 | 36 | 37 | def init_torch_seeds(seed=0): 38 | # Speed-reproducibility tradeoff https://pytorch.org/docs/stable/notes/randomness.html 39 | torch.manual_seed(seed) 40 | if seed == 0: # slower, more reproducible 41 | cudnn.benchmark, cudnn.deterministic = False, True 42 | else: # faster, less reproducible 43 | cudnn.benchmark, cudnn.deterministic = True, False 44 | 45 | 46 | def git_describe(): 47 | # return human-readable git description, i.e. v5.0-5-g3e25f1e https://git-scm.com/docs/git-describe 48 | if Path('.git').exists(): 49 | return subprocess.check_output('git describe --tags --long --always', shell=True).decode('utf-8')[:-1] 50 | else: 51 | return '' 52 | 53 | 54 | def select_device(device='', batch_size=None): 55 | # device = 'cpu' or '0' or '0,1,2,3' 56 | s = f'YOLOv5 {git_describe()} torch {torch.__version__} ' # string 57 | cpu = device.lower() == 'cpu' 58 | if cpu: 59 | os.environ['CUDA_VISIBLE_DEVICES'] = '-1' # force torch.cuda.is_available() = False 60 | elif device: # non-cpu device requested 61 | os.environ['CUDA_VISIBLE_DEVICES'] = device # set environment variable 62 | assert torch.cuda.is_available(), f'CUDA unavailable, invalid device {device} requested' # check availability 63 | 64 | cuda = not cpu and torch.cuda.is_available() 65 | if cuda: 66 | n = torch.cuda.device_count() 67 | if n > 1 and batch_size: # check that batch_size is compatible with device_count 68 | assert batch_size % n == 0, f'batch-size {batch_size} not multiple of GPU count {n}' 69 | space = ' ' * len(s) 70 | for i, d in enumerate(device.split(',') if device else range(n)): 71 | p = torch.cuda.get_device_properties(i) 72 | s += f"{'' if i == 0 else space}CUDA:{d} ({p.name}, {p.total_memory / 1024 ** 2}MB)\n" # bytes to MB 73 | else: 74 | s += 'CPU\n' 75 | 76 | logger.info(s) # skip a line 77 | return torch.device('cuda:0' if cuda else 'cpu') 78 | 79 | 80 | def time_synchronized(): 81 | # pytorch-accurate time 82 | if torch.cuda.is_available(): 83 | torch.cuda.synchronize() 84 | return time.time() 85 | 86 | 87 | def profile(x, ops, n=100, device=None): 88 | # profile a pytorch module or list of modules. Example usage: 89 | # x = torch.randn(16, 3, 640, 640) # input 90 | # m1 = lambda x: x * torch.sigmoid(x) 91 | # m2 = nn.SiLU() 92 | # profile(x, [m1, m2], n=100) # profile speed over 100 iterations 93 | 94 | device = device or torch.device('cuda:0' if torch.cuda.is_available() else 'cpu') 95 | x = x.to(device) 96 | x.requires_grad = True 97 | print(torch.__version__, device.type, torch.cuda.get_device_properties(0) if device.type == 'cuda' else '') 98 | print(f"\n{'Params':>12s}{'GFLOPS':>12s}{'forward (ms)':>16s}{'backward (ms)':>16s}{'input':>24s}{'output':>24s}") 99 | for m in ops if isinstance(ops, list) else [ops]: 100 | m = m.to(device) if hasattr(m, 'to') else m # device 101 | m = m.half() if hasattr(m, 'half') and isinstance(x, torch.Tensor) and x.dtype is torch.float16 else m # type 102 | dtf, dtb, t = 0., 0., [0., 0., 0.] # dt forward, backward 103 | try: 104 | flops = thop.profile(m, inputs=(x,), verbose=False)[0] / 1E9 * 2 # GFLOPS 105 | except: 106 | flops = 0 107 | 108 | for _ in range(n): 109 | t[0] = time_synchronized() 110 | y = m(x) 111 | t[1] = time_synchronized() 112 | try: 113 | _ = y.sum().backward() 114 | t[2] = time_synchronized() 115 | except: # no backward method 116 | t[2] = float('nan') 117 | dtf += (t[1] - t[0]) * 1000 / n # ms per op forward 118 | dtb += (t[2] - t[1]) * 1000 / n # ms per op backward 119 | 120 | s_in = tuple(x.shape) if isinstance(x, torch.Tensor) else 'list' 121 | s_out = tuple(y.shape) if isinstance(y, torch.Tensor) else 'list' 122 | p = sum(list(x.numel() for x in m.parameters())) if isinstance(m, nn.Module) else 0 # parameters 123 | print(f'{p:12.4g}{flops:12.4g}{dtf:16.4g}{dtb:16.4g}{str(s_in):>24s}{str(s_out):>24s}') 124 | 125 | 126 | def is_parallel(model): 127 | return type(model) in (nn.parallel.DataParallel, nn.parallel.DistributedDataParallel) 128 | 129 | 130 | def intersect_dicts(da, db, exclude=()): 131 | # Dictionary intersection of matching keys and shapes, omitting 'exclude' keys, using da values 132 | return {k: v for k, v in da.items() if k in db and not any(x in k for x in exclude) and v.shape == db[k].shape} 133 | 134 | 135 | def initialize_weights(model): 136 | for m in model.modules(): 137 | t = type(m) 138 | if t is nn.Conv2d: 139 | pass # nn.init.kaiming_normal_(m.weight, mode='fan_out', nonlinearity='relu') 140 | elif t is nn.BatchNorm2d: 141 | m.eps = 1e-3 142 | m.momentum = 0.03 143 | elif t in [nn.Hardswish, nn.LeakyReLU, nn.ReLU, nn.ReLU6]: 144 | m.inplace = True 145 | 146 | 147 | def find_modules(model, mclass=nn.Conv2d): 148 | # Finds layer indices matching module class 'mclass' 149 | return [i for i, m in enumerate(model.module_list) if isinstance(m, mclass)] 150 | 151 | 152 | def sparsity(model): 153 | # Return global model sparsity 154 | a, b = 0., 0. 155 | for p in model.parameters(): 156 | a += p.numel() 157 | b += (p == 0).sum() 158 | return b / a 159 | 160 | 161 | def prune(model, amount=0.3): 162 | # Prune model to requested global sparsity 163 | import torch.nn.utils.prune as prune 164 | print('Pruning model... ', end='') 165 | for name, m in model.named_modules(): 166 | if isinstance(m, nn.Conv2d): 167 | prune.l1_unstructured(m, name='weight', amount=amount) # prune 168 | prune.remove(m, 'weight') # make permanent 169 | print(' %.3g global sparsity' % sparsity(model)) 170 | 171 | 172 | def fuse_conv_and_bn(conv, bn): 173 | # Fuse convolution and batchnorm layers https://tehnokv.com/posts/fusing-batchnorm-and-conv/ 174 | fusedconv = nn.Conv2d(conv.in_channels, 175 | conv.out_channels, 176 | kernel_size=conv.kernel_size, 177 | stride=conv.stride, 178 | padding=conv.padding, 179 | groups=conv.groups, 180 | bias=True).requires_grad_(False).to(conv.weight.device) 181 | 182 | # prepare filters 183 | w_conv = conv.weight.clone().view(conv.out_channels, -1) 184 | w_bn = torch.diag(bn.weight.div(torch.sqrt(bn.eps + bn.running_var))) 185 | fusedconv.weight.copy_(torch.mm(w_bn, w_conv).view(fusedconv.weight.size())) 186 | 187 | # prepare spatial bias 188 | b_conv = torch.zeros(conv.weight.size(0), device=conv.weight.device) if conv.bias is None else conv.bias 189 | b_bn = bn.bias - bn.weight.mul(bn.running_mean).div(torch.sqrt(bn.running_var + bn.eps)) 190 | fusedconv.bias.copy_(torch.mm(w_bn, b_conv.reshape(-1, 1)).reshape(-1) + b_bn) 191 | 192 | return fusedconv 193 | 194 | 195 | def model_info(model, verbose=False, img_size=640): 196 | # Model information. img_size may be int or list, i.e. img_size=640 or img_size=[640, 320] 197 | n_p = sum(x.numel() for x in model.parameters()) # number parameters 198 | n_g = sum(x.numel() for x in model.parameters() if x.requires_grad) # number gradients 199 | if verbose: 200 | print('%5s %40s %9s %12s %20s %10s %10s' % ('layer', 'name', 'gradient', 'parameters', 'shape', 'mu', 'sigma')) 201 | for i, (name, p) in enumerate(model.named_parameters()): 202 | name = name.replace('module_list.', '') 203 | print('%5g %40s %9s %12g %20s %10.3g %10.3g' % 204 | (i, name, p.requires_grad, p.numel(), list(p.shape), p.mean(), p.std())) 205 | 206 | try: # FLOPS 207 | from thop import profile 208 | stride = int(model.stride.max()) if hasattr(model, 'stride') else 32 209 | img = torch.zeros((1, model.yaml.get('ch', 3), stride, stride), device=next(model.parameters()).device) # input 210 | flops = profile(deepcopy(model), inputs=(img,), verbose=False)[0] / 1E9 * 2 # stride GFLOPS 211 | img_size = img_size if isinstance(img_size, list) else [img_size, img_size] # expand if int/float 212 | fs = ', %.1f GFLOPS' % (flops * img_size[0] / stride * img_size[1] / stride) # 640x640 GFLOPS 213 | except (ImportError, Exception): 214 | fs = '' 215 | 216 | logger.info(f"Model Summary: {len(list(model.modules()))} layers, {n_p} parameters, {n_g} gradients{fs}") 217 | 218 | 219 | def load_classifier(name='resnet101', n=2): 220 | # Loads a pretrained model reshaped to n-class output 221 | model = torchvision.models.__dict__[name](pretrained=True) 222 | 223 | # ResNet model properties 224 | # input_size = [3, 224, 224] 225 | # input_space = 'RGB' 226 | # input_range = [0, 1] 227 | # mean = [0.485, 0.456, 0.406] 228 | # std = [0.229, 0.224, 0.225] 229 | 230 | # Reshape output to n classes 231 | filters = model.fc.weight.shape[1] 232 | model.fc.bias = nn.Parameter(torch.zeros(n), requires_grad=True) 233 | model.fc.weight = nn.Parameter(torch.zeros(n, filters), requires_grad=True) 234 | model.fc.out_features = n 235 | return model 236 | 237 | 238 | def scale_img(img, ratio=1.0, same_shape=False, gs=32): # img(16,3,256,416) 239 | # scales img(bs,3,y,x) by ratio constrained to gs-multiple 240 | if ratio == 1.0: 241 | return img 242 | else: 243 | h, w = img.shape[2:] 244 | s = (int(h * ratio), int(w * ratio)) # new size 245 | img = F.interpolate(img, size=s, mode='bilinear', align_corners=False) # resize 246 | if not same_shape: # pad/crop img 247 | h, w = [math.ceil(x * ratio / gs) * gs for x in (h, w)] 248 | return F.pad(img, [0, w - s[1], 0, h - s[0]], value=0.447) # value = imagenet mean 249 | 250 | 251 | def copy_attr(a, b, include=(), exclude=()): 252 | # Copy attributes from b to a, options to only include [...] and to exclude [...] 253 | for k, v in b.__dict__.items(): 254 | if (len(include) and k not in include) or k.startswith('_') or k in exclude: 255 | continue 256 | else: 257 | setattr(a, k, v) 258 | 259 | 260 | class ModelEMA: 261 | """ Model Exponential Moving Average from https://github.com/rwightman/pytorch-image-models 262 | Keep a moving average of everything in the model state_dict (parameters and buffers). 263 | This is intended to allow functionality like 264 | https://www.tensorflow.org/api_docs/python/tf/train/ExponentialMovingAverage 265 | A smoothed version of the weights is necessary for some training schemes to perform well. 266 | This class is sensitive where it is initialized in the sequence of model init, 267 | GPU assignment and distributed training wrappers. 268 | """ 269 | 270 | def __init__(self, model, decay=0.9999, updates=0): 271 | # Create EMA 272 | self.ema = deepcopy(model.module if is_parallel(model) else model).eval() # FP32 EMA 273 | # if next(model.parameters()).device.type != 'cpu': 274 | # self.ema.half() # FP16 EMA 275 | self.updates = updates # number of EMA updates 276 | self.decay = lambda x: decay * (1 - math.exp(-x / 2000)) # decay exponential ramp (to help early epochs) 277 | for p in self.ema.parameters(): 278 | p.requires_grad_(False) 279 | 280 | def update(self, model): 281 | # Update EMA parameters 282 | with torch.no_grad(): 283 | self.updates += 1 284 | d = self.decay(self.updates) 285 | 286 | msd = model.module.state_dict() if is_parallel(model) else model.state_dict() # model state_dict 287 | for k, v in self.ema.state_dict().items(): 288 | if v.dtype.is_floating_point: 289 | v *= d 290 | v += (1. - d) * msd[k].detach() 291 | 292 | def update_attr(self, model, include=(), exclude=('process_group', 'reducer')): 293 | # Update EMA attributes 294 | copy_attr(self.ema, model, include, exclude) 295 | -------------------------------------------------------------------------------- /src/utils/wandb_logging/__init__.py: -------------------------------------------------------------------------------- https://raw.githubusercontent.com/raghavauppuluri13/yolov5_pytorch_ros/fbd8c5d8aa5bcead2ff02445909624924ceb2026/src/utils/wandb_logging/__init__.py -------------------------------------------------------------------------------- /src/utils/wandb_logging/log_dataset.py: -------------------------------------------------------------------------------- 1 | import argparse 2 | from pathlib import Path 3 | 4 | import yaml 5 | 6 | from wandb_utils import WandbLogger 7 | from utils.datasets import LoadImagesAndLabels 8 | 9 | WANDB_ARTIFACT_PREFIX = 'wandb-artifact://' 10 | 11 | 12 | def create_dataset_artifact(opt): 13 | with open(opt.data) as f: 14 | data = yaml.load(f, Loader=yaml.SafeLoader) # data dict 15 | logger = WandbLogger(opt, '', None, data, job_type='create_dataset') 16 | nc, names = (1, ['item']) if opt.single_cls else (int(data['nc']), data['names']) 17 | names = {k: v for k, v in enumerate(names)} # to index dictionary 18 | logger.log_dataset_artifact(LoadImagesAndLabels(data['train']), names, name='train') # trainset 19 | logger.log_dataset_artifact(LoadImagesAndLabels(data['val']), names, name='val') # valset 20 | 21 | # Update data.yaml with artifact links 22 | data['train'] = WANDB_ARTIFACT_PREFIX + str(Path(opt.project) / 'train') 23 | data['val'] = WANDB_ARTIFACT_PREFIX + str(Path(opt.project) / 'val') 24 | path = opt.data if opt.overwrite_config else opt.data.replace('.', '_wandb.') # updated data.yaml path 25 | data.pop('download', None) # download via artifact instead of predefined field 'download:' 26 | with open(path, 'w') as f: 27 | yaml.dump(data, f) 28 | print("New Config file => ", path) 29 | 30 | 31 | if __name__ == '__main__': 32 | parser = argparse.ArgumentParser() 33 | parser.add_argument('--data', type=str, default='data/coco128.yaml', help='data.yaml path') 34 | parser.add_argument('--single-cls', action='store_true', help='train as single-class dataset') 35 | parser.add_argument('--project', type=str, default='YOLOv5', help='name of W&B Project') 36 | parser.add_argument('--overwrite_config', action='store_true', help='overwrite data.yaml') 37 | opt = parser.parse_args() 38 | 39 | create_dataset_artifact(opt) 40 | -------------------------------------------------------------------------------- /src/utils/wandb_logging/wandb_utils.py: -------------------------------------------------------------------------------- 1 | import json 2 | import shutil 3 | import sys 4 | from datetime import datetime 5 | from pathlib import Path 6 | 7 | import torch 8 | 9 | sys.path.append(str(Path(__file__).parent.parent.parent)) # add utils/ to path 10 | from utils.general import colorstr, xywh2xyxy 11 | 12 | try: 13 | import wandb 14 | except ImportError: 15 | wandb = None 16 | print(f"{colorstr('wandb: ')}Install Weights & Biases for YOLOv5 logging with 'pip install wandb' (recommended)") 17 | 18 | WANDB_ARTIFACT_PREFIX = 'wandb-artifact://' 19 | 20 | 21 | def remove_prefix(from_string, prefix): 22 | return from_string[len(prefix):] 23 | 24 | 25 | class WandbLogger(): 26 | def __init__(self, opt, name, run_id, data_dict, job_type='Training'): 27 | self.wandb = wandb 28 | self.wandb_run = wandb.init(config=opt, resume="allow", 29 | project='YOLOv5' if opt.project == 'runs/train' else Path(opt.project).stem, 30 | name=name, 31 | job_type=job_type, 32 | id=run_id) if self.wandb else None 33 | 34 | if job_type == 'Training': 35 | self.setup_training(opt, data_dict) 36 | if opt.bbox_interval == -1: 37 | opt.bbox_interval = (opt.epochs // 10) if opt.epochs > 10 else opt.epochs 38 | if opt.save_period == -1: 39 | opt.save_period = (opt.epochs // 10) if opt.epochs > 10 else opt.epochs 40 | 41 | def setup_training(self, opt, data_dict): 42 | self.log_dict = {} 43 | self.train_artifact_path, self.trainset_artifact = \ 44 | self.download_dataset_artifact(data_dict['train'], opt.artifact_alias) 45 | self.test_artifact_path, self.testset_artifact = \ 46 | self.download_dataset_artifact(data_dict['val'], opt.artifact_alias) 47 | self.result_artifact, self.result_table, self.weights = None, None, None 48 | if self.train_artifact_path is not None: 49 | train_path = Path(self.train_artifact_path) / 'data/images/' 50 | data_dict['train'] = str(train_path) 51 | if self.test_artifact_path is not None: 52 | test_path = Path(self.test_artifact_path) / 'data/images/' 53 | data_dict['val'] = str(test_path) 54 | self.result_artifact = wandb.Artifact("run_" + wandb.run.id + "_progress", "evaluation") 55 | self.result_table = wandb.Table(["epoch", "id", "prediction", "avg_confidence"]) 56 | if opt.resume_from_artifact: 57 | modeldir, _ = self.download_model_artifact(opt.resume_from_artifact) 58 | if modeldir: 59 | self.weights = Path(modeldir) / "best.pt" 60 | opt.weights = self.weights 61 | 62 | def download_dataset_artifact(self, path, alias): 63 | if path.startswith(WANDB_ARTIFACT_PREFIX): 64 | dataset_artifact = wandb.use_artifact(remove_prefix(path, WANDB_ARTIFACT_PREFIX) + ":" + alias) 65 | assert dataset_artifact is not None, "'Error: W&B dataset artifact doesn\'t exist'" 66 | datadir = dataset_artifact.download() 67 | labels_zip = Path(datadir) / "data/labels.zip" 68 | shutil.unpack_archive(labels_zip, Path(datadir) / 'data/labels', 'zip') 69 | print("Downloaded dataset to : ", datadir) 70 | return datadir, dataset_artifact 71 | return None, None 72 | 73 | def download_model_artifact(self, name): 74 | model_artifact = wandb.use_artifact(name + ":latest") 75 | assert model_artifact is not None, 'Error: W&B model artifact doesn\'t exist' 76 | modeldir = model_artifact.download() 77 | print("Downloaded model to : ", modeldir) 78 | return modeldir, model_artifact 79 | 80 | def log_model(self, path, opt, epoch): 81 | datetime_suffix = datetime.today().strftime('%Y-%m-%d-%H-%M-%S') 82 | model_artifact = wandb.Artifact('run_' + wandb.run.id + '_model', type='model', metadata={ 83 | 'original_url': str(path), 84 | 'epoch': epoch + 1, 85 | 'save period': opt.save_period, 86 | 'project': opt.project, 87 | 'datetime': datetime_suffix 88 | }) 89 | model_artifact.add_file(str(path / 'last.pt'), name='last.pt') 90 | model_artifact.add_file(str(path / 'best.pt'), name='best.pt') 91 | wandb.log_artifact(model_artifact) 92 | print("Saving model artifact on epoch ", epoch + 1) 93 | 94 | def log_dataset_artifact(self, dataset, class_to_id, name='dataset'): 95 | artifact = wandb.Artifact(name=name, type="dataset") 96 | image_path = dataset.path 97 | artifact.add_dir(image_path, name='data/images') 98 | table = wandb.Table(columns=["id", "train_image", "Classes"]) 99 | class_set = wandb.Classes([{'id': id, 'name': name} for id, name in class_to_id.items()]) 100 | for si, (img, labels, paths, shapes) in enumerate(dataset): 101 | height, width = shapes[0] 102 | labels[:, 2:] = (xywh2xyxy(labels[:, 2:].view(-1, 4))) 103 | labels[:, 2:] *= torch.Tensor([width, height, width, height]) 104 | box_data = [] 105 | img_classes = {} 106 | for cls, *xyxy in labels[:, 1:].tolist(): 107 | cls = int(cls) 108 | box_data.append({"position": {"minX": xyxy[0], "minY": xyxy[1], "maxX": xyxy[2], "maxY": xyxy[3]}, 109 | "class_id": cls, 110 | "box_caption": "%s" % (class_to_id[cls]), 111 | "scores": {"acc": 1}, 112 | "domain": "pixel"}) 113 | img_classes[cls] = class_to_id[cls] 114 | boxes = {"ground_truth": {"box_data": box_data, "class_labels": class_to_id}} # inference-space 115 | table.add_data(si, wandb.Image(paths, classes=class_set, boxes=boxes), json.dumps(img_classes)) 116 | artifact.add(table, name) 117 | labels_path = 'labels'.join(image_path.rsplit('images', 1)) 118 | zip_path = Path(labels_path).parent / (name + '_labels.zip') 119 | if not zip_path.is_file(): # make_archive won't check if file exists 120 | shutil.make_archive(zip_path.with_suffix(''), 'zip', labels_path) 121 | artifact.add_file(str(zip_path), name='data/labels.zip') 122 | wandb.log_artifact(artifact) 123 | print("Saving data to W&B...") 124 | 125 | def log(self, log_dict): 126 | if self.wandb_run: 127 | for key, value in log_dict.items(): 128 | self.log_dict[key] = value 129 | 130 | def end_epoch(self): 131 | if self.wandb_run and self.log_dict: 132 | wandb.log(self.log_dict) 133 | self.log_dict = {} 134 | 135 | def finish_run(self): 136 | if self.wandb_run: 137 | if self.result_artifact: 138 | print("Add Training Progress Artifact") 139 | self.result_artifact.add(self.result_table, 'result') 140 | train_results = wandb.JoinedTable(self.testset_artifact.get("val"), self.result_table, "id") 141 | self.result_artifact.add(train_results, 'joined_result') 142 | wandb.log_artifact(self.result_artifact) 143 | if self.log_dict: 144 | wandb.log(self.log_dict) 145 | wandb.run.finish() 146 | --------------------------------------------------------------------------------