diff --git a/.github/ISSUE_TEMPLATE/bug_report.md b/.github/ISSUE_TEMPLATE/bug_report.md new file mode 100644 index 000000000..917ac5cab --- /dev/null +++ b/.github/ISSUE_TEMPLATE/bug_report.md @@ -0,0 +1,33 @@ +--- +name: 🐛 Bug report +about: Create a report to help us improve +title: "" +labels: bug +assignees: '' + +--- + +**Describe the bug** +A clear and concise description of what the bug is. + +**To Reproduce** +Steps to reproduce the behavior: +1. Go to '...' +2. Click on '....' +3. Scroll down to '....' +4. See error + +**Expected behavior** +A clear and concise description of what you expected to happen. + +**Screenshots** +If applicable, add screenshots to help explain your problem. + +**System specs (please complete the following information):** + - OS + - ROS version + - Library versions when non-standard + - GPU / CUDA version when relevant + +**Additional context** +Add any other context about the problem here. diff --git a/.github/ISSUE_TEMPLATE/compilation-and-runtime-issue.md b/.github/ISSUE_TEMPLATE/compilation-and-runtime-issue.md new file mode 100644 index 000000000..e86674bd6 --- /dev/null +++ b/.github/ISSUE_TEMPLATE/compilation-and-runtime-issue.md @@ -0,0 +1,32 @@ +--- +name: ⁉️ Compilation and runtime issue +about: Use this template if you're facing issues running or compiling darknet_ros. +title: "" +labels: question +assignees: '' + +--- + +**Describe the bug** +A clear and concise description of what the bug is. + +**To Reproduce** +Steps to reproduce the behavior: +1. Go to '...' +2. Click on '....' +3. Scroll down to '....' +4. See error + +**Expected behavior** +A clear and concise description of what you expected to happen. + +**Screenshots** +If applicable, add screenshots to help explain your problem. + +**System (please complete the following information):** + - OS: [e.g. Ubuntu 20.04] + - ROS version: [e.g., Noetic, Foxy] + - GPU when relevant: [e.g., Intel UHD, NVidia GTX 3090] + +**Additional context** +Add any other context about the problem here. diff --git a/.github/ISSUE_TEMPLATE/feature_request.md b/.github/ISSUE_TEMPLATE/feature_request.md new file mode 100644 index 000000000..d20dc6d37 --- /dev/null +++ b/.github/ISSUE_TEMPLATE/feature_request.md @@ -0,0 +1,20 @@ +--- +name: ✨ Feature request +about: Suggest an idea for this project +title: "" +labels: enhancement +assignees: mbjelonic + +--- + +**Is your feature request related to a problem? Please describe.** +A clear and concise description of what the problem is. Ex. I'm always frustrated when [...] + +**Describe the solution you'd like** +A clear and concise description of what you want to happen. + +**Describe alternatives you've considered** +A clear and concise description of any alternative solutions or features you've considered. + +**Additional context** +Add any other context or screenshots about the feature request here. diff --git a/.gitignore b/.gitignore new file mode 100644 index 000000000..608b1d449 --- /dev/null +++ b/.gitignore @@ -0,0 +1,2 @@ +.vscode/ +build/ \ No newline at end of file diff --git a/.gitmodules b/.gitmodules index 000b92b76..0957ef07f 100644 --- a/.gitmodules +++ b/.gitmodules @@ -1,3 +1,3 @@ [submodule "darknet"] - path = darknet - url = https://github.com/pjreddie/darknet + path = darknet + url = https://github.com/AlexeyAB/darknet diff --git a/README.md b/README.md index b78ad2334..af6b4de2e 100644 --- a/README.md +++ b/README.md @@ -2,9 +2,11 @@ ## Overview -This is a ROS package developed for object detection in camera images. You only look once (YOLO) is a state-of-the-art, real-time object detection system. In the following ROS package you are able to use YOLO (V3) on GPU and CPU. The pre-trained model of the convolutional neural network is able to detect pre-trained classes including the data set from VOC and COCO, or you can also create a network with your own detection objects. For more information about YOLO, Darknet, available training data and training YOLO see the following link: [YOLO: Real-Time Object Detection](http://pjreddie.com/darknet/yolo/). +This is a ROS package developed for **object detection in camera images**. You only look once (YOLO) is a state-of-the-art, real-time object detection system. In the following ROS package you are able to use **YOLO (V3) on GPU and CPU**. The pre-trained model of the convolutional neural network is able to detect pre-trained classes including the data set from VOC and COCO, or you can also create a network with your own detection objects. For more information about YOLO, Darknet, available training data and training YOLO see the following link: [YOLO: Real-Time Object Detection](http://pjreddie.com/darknet/yolo/). -The YOLO packages have been tested under ROS Foxy, Ubuntu 20.04 and OpenCV 4.2.0. This is research code, expect that it changes often and any fitness for a particular purpose is disclaimed. +The YOLO packages have been tested under **ROS Noetic** and **Ubuntu 20.04**. Note: We also provide branches that work under **ROS Melodic**, **ROS Foxy** and **ROS2**. + +This is research code, expect that it changes often and any fitness for a particular purpose is disclaimed. **Author: [Marko Bjelonic](https://www.markobjelonic.com), marko.bjelonic@mavt.ethz.ch** @@ -113,7 +115,7 @@ In order to use your own detection objects you need to provide your weights and ## Basic Usage -In order to get YOLO ROS: Real-Time Object Detection for ROS to run with your robot, you will need to adapt a few parameters. It is the easiest if duplicate and adapt all the parameter files that you need to change from the `darkned_ros` package. These are specifically the parameter files in `config` and the launch file from the `launch` folder. +In order to get YOLO ROS: Real-Time Object Detection for ROS to run with your robot, you will need to adapt a few parameters. It is the easiest if duplicate and adapt all the parameter files that you need to change from the `darknet_ros` package. These are specifically the parameter files in `config` and the launch file from the `launch` folder. ## Nodes @@ -123,7 +125,7 @@ This is the main YOLO ROS: Real-Time Object Detection for ROS node. It uses the ### ROS related parameters -You can change the names and other parameters of the publishers, subscribers and actions inside `darkned_ros/config/ros.yaml`. +You can change the names and other parameters of the publishers, subscribers and actions inside `darknet_ros/config/ros.yaml`. #### Subscribed Topics @@ -153,7 +155,7 @@ You can change the names and other parameters of the publishers, subscribers and ### Detection related parameters -You can change the parameters that are related to the detection by adding a new config file that looks similar to `darkned_ros/config/yolo.yaml`. +You can change the parameters that are related to the detection by adding a new config file that looks similar to `darknet_ros/config/yolo.yaml`. * **`image_view/enable_opencv`** (bool) @@ -165,11 +167,11 @@ You can change the parameters that are related to the detection by adding a new * **`yolo_model/config_file/name`** (string) - Name of the cfg file of the network that is used for detection. The code searches for this name inside `darkned_ros/yolo_network_config/cfg/`. + Name of the cfg file of the network that is used for detection. The code searches for this name inside `darknet_ros/yolo_network_config/cfg/`. * **`yolo_model/weight_file/name`** (string) - Name of the weights file of the network that is used for detection. The code searches for this name inside `darkned_ros/yolo_network_config/weights/`. + Name of the weights file of the network that is used for detection. The code searches for this name inside `darknet_ros/yolo_network_config/weights/`. * **`yolo_model/threshold/value`** (float) @@ -177,4 +179,4 @@ You can change the parameters that are related to the detection by adding a new * **`yolo_model/detection_classes/names`** (array of strings) - Detection names of the network used by the cfg and weights file inside `darkned_ros/yolo_network_config/`. + Detection names of the network used by the cfg and weights file inside `darknet_ros/yolo_network_config/`. \ No newline at end of file diff --git a/darknet b/darknet index 508381b37..25505164a 160000 --- a/darknet +++ b/darknet @@ -1 +1 @@ -Subproject commit 508381b37fe75e0e1a01bcb2941cb0b31eb0e4c9 +Subproject commit 25505164a3bd6235c75deaad325878ceda90249a diff --git a/darknet_ros/CHANGELOG.rst b/darknet_ros/CHANGELOG.rst index bee27cf0b..d84386aa8 100644 --- a/darknet_ros/CHANGELOG.rst +++ b/darknet_ros/CHANGELOG.rst @@ -2,6 +2,54 @@ Changelog for package darknet_ros ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.5 (2021-04-08) +------------------ +* Merge pull request `#308 `_ from leggedrobotics/noetic + Noetic +* Minor fix in CMake. +* Minor fix in test. +* Updated readme. +* Updated to newest darknet and fixed opencv on Ubuntu 20.04. +* First changes in CMakeLists. +* Merge pull request `#287 `_ from leggedrobotics/feature/nodeletize + Feature/nodeletize +* Small adjustments +* Added pointer deletion in destructor and minor formatting +* Minor formatting +* Adding option to use nodelet +* Add libxext +* Add libxt-dev +* Retrieve binaries from Github releases +* Merge pull request `#232 `_ from leggedrobotics/add-required-deps + Update package.xml dependencies +* Don't require cmake-clang-tools +* Update package.xml dependencies +* Added clang tooling. +* Merge pull request `#207 `_ from umdlife/install_weights + Add install targets for configuration files +* Add install targets for configuration files + Adds the `launch`, `config`, and `yolo_network_config` folders to the + install target for `darknet_ros` so they are available in the catkin + install directory. +* Fixed linking of cuda libraries. +* Merge branch 'kunaltyagi-cleanup' +* Cleaned up CMakeLists.txt, used OpenCV C++ API for cpp file +* Merge pull request `#189 `_ from martinspedro/master + /darknet_ros/found_object uses custom msg with Header for improving synchronization +* YOLO publishes Object Count with Time stamp using custom msg with Header +* Merge pull request `#183 `_ from kunaltyagi/id_num + Add numerical ID and launch param for image +* Adding numerical ID and launch param for image +* Merge pull request `#182 `_ from leggedrobotics/fix/image_publisher + Fixed copy of image publisher. +* Fixed copy of image publisher. +* Merge branch 'kjbilton-master' +* Increased scope of image acquisition mutex to prevent image overwriting +* Merge branch 'utra-robosoccer-master' +* Removed warnings caused by catkin builds +* Added test_depend of wget to accomodate Jenkins. +* Contributors: Jason Wang, Kunal Tyagi, Kyle Bilton, Marko Bjelonic, Pedro Martins, Tom Lankhorst, Tomas Gareau, timonh + 1.1.4 (2019-03-03) ------------------ * Merge pull request `#141 `_ from lorenwel/feature/launch_file_arg diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 56dbad55a..43758d444 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -1,38 +1,101 @@ cmake_minimum_required(VERSION 3.5) project(darknet_ros) +include(CMakeDependentOption) + set(CMAKE_CXX_STANDARD 17) -# Define path of darknet folder here. +# USER SETTINGS ================================================================= + +set(CUDA_ENABLE ON) +set(CUDNN_ENABLE ON) # set(CUDNN_ENABLE ON) +set(FP16_ENABLE ON) + +set(DOWNLOAD_YOLOV2_TINY OFF) +set(DOWNLOAD_YOLOV3 OFF) +set(DOWNLOAD_YOLOV4 OFF) +set(DOWNLOAD_YOLOV4_CSP ON) +set(DOWNLOAD_YOLOV4_TINY ON) +set(DOWNLOAD_YOLOV4_MISH OFF) +set(DOWNLOAD_YOLOV7_TINY ON) + +# Jetson AGX Xavier & TITAN V is under version of Turing. So, please set manually. +# Turing or Ampere GPUs, FP16 is automatically enabled. + +# set(CMAKE_CUDA_ARCHITECTURES 72) + + +# Define path of darknet folder here. =========================================== find_path(DARKNET_PATH NAMES "README.md" HINTS "${CMAKE_CURRENT_SOURCE_DIR}/../darknet/") message(STATUS "Darknet path dir = ${DARKNET_PATH}") add_definitions(-DDARKNET_FILE_PATH="${DARKNET_PATH}") -# Find CUDA -find_package(CUDA QUIET) -if (CUDA_FOUND) +# Find CUDA ==================================================================== +if(CUDA_ENABLE) find_package(CUDA REQUIRED) +endif() + +if (CUDA_FOUND) message(STATUS "CUDA Version: ${CUDA_VERSION_STRINGS}") message(STATUS "CUDA Libararies: ${CUDA_LIBRARIES}") set( CUDA_NVCC_FLAGS ${CUDA_NVCC_FLAGS}; -O3 - -gencode arch=compute_30,code=sm_30 - -gencode arch=compute_35,code=sm_35 -gencode arch=compute_50,code=[sm_50,compute_50] -gencode arch=compute_52,code=[sm_52,compute_52] - -gencode arch=compute_61,code=sm_61 - -gencode arch=compute_62,code=sm_62 + -gencode arch=compute_61,code=[sm_61,compute_61] + -gencode arch=compute_72,code=[sm_72,compute_72] # Jetson AGX Xavier or TITAN V + -gencode arch=compute_75,code=[sm_75,compute_75] + -gencode arch=compute_80,code=[sm_80,compute_80] + -gencode arch=compute_86,code=[sm_86,compute_86] # GeForce RTX 3000 Series + -gencode arch=compute_87,code=[sm_87,compute_87] ) add_definitions(-DGPU) +endif() + +# Find CUDNN ======================================================================= + +set(CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/../darknet/cmake/Modules/" ${CMAKE_MODULE_PATH}) + +if(CUDNN_ENABLE) + find_package(CUDNN) + message(STATUS "cuDNN Version: ${CUDNN_VERSION_STRINGS}") + message(STATUS "cuDNN Libararies: ${CUDNN_LIBRARIES}") +endif() + +if(CUDNN_FOUND) + set(ADDITIONAL_CXX_FLAGS "${ADDITIONAL_CXX_FLAGS} -DCUDNN") +endif() + +execute_process ( + COMMAND bash -c "lspci | grep NVIDIA | grep -e TU106 -e TU104 -e TU102 -e GA106 -e GA104 -e GA102" + OUTPUT_VARIABLE outVar +) +message ( STATUS " GPU (FP16): " ${outVar} ) +if(outVar AND FP16_ENABLE) + set(CMAKE_CUDA_ARCHITECTURES 75) +endif() + +if ( 70 IN_LIST CMAKE_CUDA_ARCHITECTURES OR + 72 IN_LIST CMAKE_CUDA_ARCHITECTURES OR + 75 IN_LIST CMAKE_CUDA_ARCHITECTURES OR + 80 IN_LIST CMAKE_CUDA_ARCHITECTURES OR + 86 IN_LIST CMAKE_CUDA_ARCHITECTURES) + set(ENABLE_CUDNN_HALF "TRUE" CACHE BOOL "Enable CUDNN Half precision" FORCE) + message(STATUS "Your setup supports half precision (CUDA_ARCHITECTURES >= 70)") else() - list(APPEND LIBRARIES "m") + set(ENABLE_CUDNN_HALF "FALSE" CACHE BOOL "Enable CUDNN Half precision" FORCE) + message(STATUS "Your setup does not support half precision (it requires CUDA_ARCHITECTURES >= 70)") endif() -# Find X11 +# else() +# list(APPEND LIBRARIES "m") +# endif() + +# Find X11 ============================================================================ message ( STATUS "Searching for X11..." ) find_package ( X11 REQUIRED ) if ( X11_FOUND ) @@ -76,55 +139,64 @@ add_definitions(-O4 -g) include_directories( ${DARKNET_PATH}/src ${DARKNET_PATH}/include + ${DARKNET_PATH}/3rdparty/stb/include include ${catkin_INCLUDE_DIRS} ) set(PROJECT_LIB_FILES - src/YoloObjectDetector.cpp src/image_interface.c + src/YoloObjectDetector.cpp src/image_interface.cpp + src/yolo_object_detector_node.cpp ) set(DARKNET_CORE_FILES - ${DARKNET_PATH}/src/activation_layer.c ${DARKNET_PATH}/src/im2col.c - ${DARKNET_PATH}/src/activations.c ${DARKNET_PATH}/src/image.c - ${DARKNET_PATH}/src/avgpool_layer.c ${DARKNET_PATH}/src/layer.c - ${DARKNET_PATH}/src/batchnorm_layer.c ${DARKNET_PATH}/src/list.c - ${DARKNET_PATH}/src/blas.c ${DARKNET_PATH}/src/local_layer.c - ${DARKNET_PATH}/src/box.c ${DARKNET_PATH}/src/lstm_layer.c - ${DARKNET_PATH}/src/col2im.c ${DARKNET_PATH}/src/matrix.c - ${DARKNET_PATH}/src/connected_layer.c ${DARKNET_PATH}/src/maxpool_layer.c - ${DARKNET_PATH}/src/convolutional_layer.c ${DARKNET_PATH}/src/network.c - ${DARKNET_PATH}/src/cost_layer.c ${DARKNET_PATH}/src/normalization_layer.c - ${DARKNET_PATH}/src/crnn_layer.c ${DARKNET_PATH}/src/option_list.c - ${DARKNET_PATH}/src/crop_layer.c ${DARKNET_PATH}/src/parser.c - ${DARKNET_PATH}/src/cuda.c ${DARKNET_PATH}/src/region_layer.c - ${DARKNET_PATH}/src/data.c ${DARKNET_PATH}/src/reorg_layer.c - ${DARKNET_PATH}/src/deconvolutional_layer.c ${DARKNET_PATH}/src/rnn_layer.c - ${DARKNET_PATH}/src/demo.c ${DARKNET_PATH}/src/route_layer.c - ${DARKNET_PATH}/src/detection_layer.c ${DARKNET_PATH}/src/shortcut_layer.c - ${DARKNET_PATH}/src/dropout_layer.c ${DARKNET_PATH}/src/softmax_layer.c - ${DARKNET_PATH}/src/gemm.c ${DARKNET_PATH}/src/tree.c - ${DARKNET_PATH}/src/gru_layer.c ${DARKNET_PATH}/src/utils.c - ${DARKNET_PATH}/src/upsample_layer.c ${DARKNET_PATH}/src/logistic_layer.c - ${DARKNET_PATH}/src/l2norm_layer.c ${DARKNET_PATH}/src/yolo_layer.c - - ${DARKNET_PATH}/examples/art.c ${DARKNET_PATH}/examples/lsd.c - ${DARKNET_PATH}/examples/attention.c ${DARKNET_PATH}/examples/nightmare.c - ${DARKNET_PATH}/examples/captcha.c ${DARKNET_PATH}/examples/regressor.c - ${DARKNET_PATH}/examples/cifar.c ${DARKNET_PATH}/examples/rnn.c - ${DARKNET_PATH}/examples/classifier.c ${DARKNET_PATH}/examples/segmenter.c - ${DARKNET_PATH}/examples/coco.c ${DARKNET_PATH}/examples/super.c - ${DARKNET_PATH}/examples/darknet.c ${DARKNET_PATH}/examples/tag.c - ${DARKNET_PATH}/examples/detector.c ${DARKNET_PATH}/examples/yolo.c - ${DARKNET_PATH}/examples/go.c + ${DARKNET_PATH}/src/activation_layer.c ${DARKNET_PATH}/src/activations.c + ${DARKNET_PATH}/src/art.c ${DARKNET_PATH}/src/avgpool_layer.c + ${DARKNET_PATH}/src/batchnorm_layer.c ${DARKNET_PATH}/src/blas.c + ${DARKNET_PATH}/src/box.c ${DARKNET_PATH}/src/captcha.c + ${DARKNET_PATH}/src/cifar.c ${DARKNET_PATH}/src/classifier.c + ${DARKNET_PATH}/src/coco.c ${DARKNET_PATH}/src/col2im.c + ${DARKNET_PATH}/src/compare.c ${DARKNET_PATH}/src/connected_layer.c + ${DARKNET_PATH}/src/conv_lstm_layer.c ${DARKNET_PATH}/src/convolutional_layer.c + ${DARKNET_PATH}/src/cost_layer.c ${DARKNET_PATH}/src/cpu_gemm.c + ${DARKNET_PATH}/src/crnn_layer.c ${DARKNET_PATH}/src/crop_layer.c + ${DARKNET_PATH}/src/dark_cuda.c ${DARKNET_PATH}/src/darknet.c + ${DARKNET_PATH}/src/data.c ${DARKNET_PATH}/src/deconvolutional_layer.c + ${DARKNET_PATH}/src/demo.c ${DARKNET_PATH}/src/detection_layer.c + ${DARKNET_PATH}/src/detector.c ${DARKNET_PATH}/src/dice.c + ${DARKNET_PATH}/src/dropout_layer.c ${DARKNET_PATH}/src/gaussian_yolo_layer.c + ${DARKNET_PATH}/src/gemm.c ${DARKNET_PATH}/src/getopt.c + ${DARKNET_PATH}/src/gettimeofday.c ${DARKNET_PATH}/src/go.c + ${DARKNET_PATH}/src/gru_layer.c ${DARKNET_PATH}/src/http_stream.cpp + ${DARKNET_PATH}/src/im2col.c ${DARKNET_PATH}/src/image.c + ${DARKNET_PATH}/src/image_opencv.cpp ${DARKNET_PATH}/src/layer.c + ${DARKNET_PATH}/src/list.c ${DARKNET_PATH}/src/local_layer.c + ${DARKNET_PATH}/src/lstm_layer.c ${DARKNET_PATH}/src/matrix.c + ${DARKNET_PATH}/src/maxpool_layer.c ${DARKNET_PATH}/src/network.c + ${DARKNET_PATH}/src/nightmare.c ${DARKNET_PATH}/src/normalization_layer.c + ${DARKNET_PATH}/src/option_list.c ${DARKNET_PATH}/src/parser.c + ${DARKNET_PATH}/src/region_layer.c ${DARKNET_PATH}/src/reorg_layer.c + ${DARKNET_PATH}/src/reorg_old_layer.c ${DARKNET_PATH}/src/rnn.c + ${DARKNET_PATH}/src/rnn_layer.c ${DARKNET_PATH}/src/rnn_vid.c + ${DARKNET_PATH}/src/route_layer.c ${DARKNET_PATH}/src/sam_layer.c + ${DARKNET_PATH}/src/scale_channels_layer.c ${DARKNET_PATH}/src/shortcut_layer.c + ${DARKNET_PATH}/src/softmax_layer.c ${DARKNET_PATH}/src/super.c + ${DARKNET_PATH}/src/swag.c ${DARKNET_PATH}/src/tag.c + ${DARKNET_PATH}/src/tree.c ${DARKNET_PATH}/src/upsample_layer.c + ${DARKNET_PATH}/src/utils.c ${DARKNET_PATH}/src/voxel.c + ${DARKNET_PATH}/src/writing.c ${DARKNET_PATH}/src/yolo.c + ${DARKNET_PATH}/src/yolo_layer.c ${DARKNET_PATH}/src/representation_layer.c + + ) set(DARKNET_CUDA_FILES - ${DARKNET_PATH}/src/activation_kernels.cu ${DARKNET_PATH}/src/crop_layer_kernels.cu - ${DARKNET_PATH}/src/avgpool_layer_kernels.cu ${DARKNET_PATH}/src/deconvolutional_kernels.cu - ${DARKNET_PATH}/src/blas_kernels.cu ${DARKNET_PATH}/src/dropout_layer_kernels.cu - ${DARKNET_PATH}/src/col2im_kernels.cu ${DARKNET_PATH}/src/im2col_kernels.cu - ${DARKNET_PATH}/src/convolutional_kernels.cu ${DARKNET_PATH}/src/maxpool_layer_kernels.cu + ${DARKNET_PATH}/src/activation_kernels.cu ${DARKNET_PATH}/src/avgpool_layer_kernels.cu + ${DARKNET_PATH}/src/blas_kernels.cu ${DARKNET_PATH}/src/col2im_kernels.cu + ${DARKNET_PATH}/src/convolutional_kernels.cu ${DARKNET_PATH}/src/crop_layer_kernels.cu + ${DARKNET_PATH}/src/deconvolutional_kernels.cu ${DARKNET_PATH}/src/dropout_layer_kernels.cu + ${DARKNET_PATH}/src/im2col_kernels.cu ${DARKNET_PATH}/src/maxpool_layer_kernels.cu + ${DARKNET_PATH}/src/network_kernels.cu ) set_source_files_properties(${PROJECT_LIB_FILES} PROPERTIES LANGUAGE CXX) @@ -142,27 +214,51 @@ if (CUDA_FOUND) ament_target_dependencies(${PROJECT_NAME}_lib ${dependencies}) - target_link_libraries(${PROJECT_NAME}_lib - cuda - cudart - cublas - curand - ) + if(CUDNN_FOUND) + if(ENABLE_CUDNN_HALF) + target_link_libraries(${PROJECT_NAME}_lib + cuda + cudart + cublas + curand + CuDNN::CuDNN + ) + target_compile_definitions(${PROJECT_NAME}_lib PRIVATE + -DCUDNN + -DCUDNN_HALF + ) + else() + target_link_libraries(${PROJECT_NAME}_lib + cuda + cudart + cublas + curand + CuDNN::CuDNN + ) + target_compile_definitions(${PROJECT_NAME}_lib PRIVATE + -DCUDNN + ) + endif() + else() + target_link_libraries(${PROJECT_NAME}_lib + cuda + cudart + cublas + curand + ) + endif() cuda_add_executable(${PROJECT_NAME} src/yolo_object_detector_node.cpp ) - ament_target_dependencies(${PROJECT_NAME} ${dependencies}) +ament_target_dependencies(${PROJECT_NAME} ${dependencies}) else() - add_library(${PROJECT_NAME}_core_lib - ${DARKNET_CORE_FILES} - ) - add_library(${PROJECT_NAME}_lib ${PROJECT_LIB_FILES} + ${DARKNET_CORE_FILES} ) ament_target_dependencies(${PROJECT_NAME}_lib ${dependencies}) target_compile_definitions(${PROJECT_NAME}_lib PRIVATE -DOPENCV) @@ -174,6 +270,13 @@ else() endif() +find_package(OpenMP) + +if (OPENMP_FOUND) + set(CMAKE_C_FLAGS "${CMAKE_C_FLAGS} ${OpenMP_C_FLAGS}") + set(CMAKE_CXX_FLAGS "${CMAKE_CXX_FLAGS} ${OpenMP_CXX_FLAGS}") +endif() + target_link_libraries(${PROJECT_NAME}_lib m pthread @@ -186,7 +289,6 @@ target_compile_definitions(${PROJECT_NAME}_lib PRIVATE -DOPENCV) target_link_libraries(${PROJECT_NAME} ${PROJECT_NAME}_lib - ${PROJECT_NAME}_core_lib ) target_compile_definitions(${PROJECT_NAME} PRIVATE -DOPENCV) @@ -205,19 +307,84 @@ install( # Download yolov2-tiny.weights set(PATH "${CMAKE_CURRENT_SOURCE_DIR}/yolo_network_config/weights") -set(FILE "${PATH}/yolov2-tiny.weights") -message(STATUS "Checking and downloading yolov2-tiny.weights if needed ...") -if (NOT EXISTS "${FILE}") - message(STATUS "... file does not exist. Downloading now ...") - execute_process(COMMAND wget http://pjreddie.com/media/files/yolov2-tiny.weights -P ${PATH}) + +if(DOWNLOAD_YOLOV2_TINY) + set(FILE "${PATH}/yolov2-tiny.weights") + message(STATUS "Checking and downloading yolov2-tiny.weights if needed ...") + if (NOT EXISTS "${FILE}") + message(STATUS "... file does not exist. Downloading now ...") + # yolov2-tiny.cfg is already in the repo. + execute_process(COMMAND wget http://pjreddie.com/media/files/yolov2-tiny.weights -P ${PATH}) + endif() + message(STATUS "Done.") endif() # Download yolov3.weights -set(FILE "${PATH}/yolov3.weights") -message(STATUS "Checking and downloading yolov3.weights if needed ...") -if (NOT EXISTS "${FILE}") - message(STATUS "... file does not exist. Downloading now ...") - execute_process(COMMAND wget http://pjreddie.com/media/files/yolov3.weights -P ${PATH}) +if(DOWNLOAD_YOLOV3) + set(FILE "${PATH}/yolov3.weights") + message(STATUS "Checking and downloading yolov3.weights if needed ...") + if (NOT EXISTS "${FILE}") + message(STATUS "... file does not exist. Downloading now ...") + # yolov3.cfg is already in the repo. + execute_process(COMMAND wget http://pjreddie.com/media/files/yolov3.weights -P ${PATH}) + endif() + message(STATUS "Done.") +endif() + +# Download yolov4.weights +if(DOWNLOAD_YOLOV4) + set(FILE "${PATH}/yolov4.weights") + message(STATUS "Checking and downloading yolov4.weights if needed ...") + if (NOT EXISTS "${FILE}") + message(STATUS "... file does not exist. Downloading now ...") + execute_process(COMMAND wget -q https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v3_optimal/yolov4.weights -P ${PATH}) + endif() + message(STATUS "Done.") +endif() + +# Download yolov4-tiny.weights +if(DOWNLOAD_YOLOV4_TINY) + set(FILE "${PATH}/yolov4-tiny.weights") + message(STATUS "Checking and downloading yolov4-tiny.weights if needed ...") + if (NOT EXISTS "${FILE}") + message(STATUS "... file does not exist. Downloading now ...") + # yolov4.cfg is already in the repo. + execute_process(COMMAND wget -q https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v4_pre/yolov4-tiny.weights -P ${PATH}) + endif() + message(STATUS "Done.") +endif() + +# Download yolov4-csp.weights +if(DOWNLOAD_YOLOV4_CSP) + set(FILE "${PATH}/yolov4-csp.weights") + message(STATUS "Checking and downloading yolov4-csp.weights if needed ...") + if (NOT EXISTS "${FILE}") + message(STATUS "... file does not exist. Downloading now ...") + execute_process(COMMAND wget -q https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v4_pre/yolov4-csp.weights -P ${PATH}) + endif() + message(STATUS "Done.") +endif() + +# Download yolov4-mish.weights + +if(DOWNLOAD_YOLOV4_MISH) + set(FILE "${PATH}/yolov4-mish.weights") + message(STATUS "Checking and downloading yolov4-mish.weights if needed ...") + if (NOT EXISTS "${FILE}") + message(STATUS "... file does not exist. Downloading now ...") + execute_process(COMMAND wget -q https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v4_pre/yolov4x-mish.weights -P ${PATH}) + endif() + message(STATUS "Done.") +endif() + +if(DOWNLOAD_YOLOV7_TINY) + set(FILE "${PATH}/yolov7-tiny.weights") + message(STATUS "Checking and downloading yolov7-tiny.weights if needed ...") + if (NOT EXISTS "${FILE}") + message(STATUS "... file does not exist. Downloading now ...") + execute_process(COMMAND wget -q https://github.com/AlexeyAB/darknet/releases/download/yolov4/yolov7-tiny.weights -P ${PATH}) + endif() + message(STATUS "Done.") endif() install(DIRECTORY yolo_network_config/cfg yolo_network_config/weights DESTINATION share/${PROJECT_NAME}/yolo_network_config/) @@ -227,21 +394,21 @@ install(DIRECTORY launch config DESTINATION share/${PROJECT_NAME}/) ## Testing ## ############# -if(BUILD_TESTING) - # Download yolov2.weights - set(PATH "${CMAKE_CURRENT_SOURCE_DIR}/yolo_network_config/weights") - set(FILE "${PATH}/yolov2.weights") - message(STATUS "Checking and downloading yolov2.weights if needed ...") - if (NOT EXISTS "${FILE}") - message(STATUS "... file does not exist. Downloading now ...") - execute_process(COMMAND wget http://pjreddie.com/media/files/yolov2.weights -P ${PATH}) - endif() +# if(BUILD_TESTING) +# # Download yolov2.weights +# set(PATH "${CMAKE_CURRENT_SOURCE_DIR}/yolo_network_config/weights") +# set(FILE "${PATH}/yolov2.weights") +# message(STATUS "Checking and downloading yolov2.weights if needed ...") +# if (NOT EXISTS "${FILE}") +# message(STATUS "... file does not exist. Downloading now ...") +# execute_process(COMMAND wget http://pjreddie.com/media/files/yolov2.weights -P ${PATH}) +# endif() - find_package(ament_lint_auto REQUIRED) - ament_lint_auto_find_test_dependencies() +# find_package(ament_lint_auto REQUIRED) +# ament_lint_auto_find_test_dependencies() + +# find_package(ament_cmake_gtest REQUIRED) - find_package(ament_cmake_gtest REQUIRED) - #ament_add_gtest(${PROJECT_NAME}_object_detection-test # test/object_detection.test # test/test_main.cpp @@ -250,11 +417,11 @@ if(BUILD_TESTING) #target_link_libraries(${PROJECT_NAME}_object_detection-test # ${PROJECT_NAME}_lib #) -endif() +# endif() ament_export_include_directories(include) ament_export_libraries(${PROJECT_NAME}_lib) ament_export_dependencies(${dependencies}) -ament_package() \ No newline at end of file +ament_package() diff --git a/darknet_ros/config/ros.yaml b/darknet_ros/config/ros.yaml index 6562e3164..7b5a90c16 100644 --- a/darknet_ros/config/ros.yaml +++ b/darknet_ros/config/ros.yaml @@ -2,7 +2,7 @@ darknet_ros: ros__parameters: subscribers: camera_reading: - topic: /camera/rgb/image_raw + topic: /image_raw queue_size: 1 actions: camera_reading: diff --git a/darknet_ros/config/yolov2-tiny-voc.yaml b/darknet_ros/config/yolov2-tiny-voc.yaml deleted file mode 100644 index b0a641df0..000000000 --- a/darknet_ros/config/yolov2-tiny-voc.yaml +++ /dev/null @@ -1,33 +0,0 @@ -darknet_ros: - ros__parameters: - yolo_model: - - config_file: - name: yolov2-tiny-voc.cfg - weight_file: - name: yolov2-tiny-voc.weights - threshold: - value: 0.3 - detection_classes: - names: - - aeroplane - - bicycle - - bird - - boat - - bottle - - bus - - car - - cat - - chair - - cow - - diningtable - - dog - - horse - - motorbike - - person - - pottedplant - - sheep - - sofa - - train - - tvmonitor - \ No newline at end of file diff --git a/darknet_ros/config/yolov2-voc.yaml b/darknet_ros/config/yolov2-voc.yaml deleted file mode 100644 index 3b009b705..000000000 --- a/darknet_ros/config/yolov2-voc.yaml +++ /dev/null @@ -1,32 +0,0 @@ -darknet_ros: - ros__parameters: - yolo_model: - - config_file: - name: yolov2-voc.cfg - weight_file: - name: yolov2-voc.weights - threshold: - value: 0.3 - detection_classes: - names: - - aeroplane - - bicycle - - bird - - boat - - bottle - - bus - - car - - cat - - chair - - cow - - diningtable - - dog - - horse - - motorbike - - person - - pottedplant - - sheep - - sofa - - train - - tvmonitor diff --git a/darknet_ros/config/yolov3-voc.yaml b/darknet_ros/config/yolov3-voc.yaml deleted file mode 100644 index 51a2a64dd..000000000 --- a/darknet_ros/config/yolov3-voc.yaml +++ /dev/null @@ -1,32 +0,0 @@ -darknet_ros: - ros__parameters: - yolo_model: - - config_file: - name: yolov3-voc.cfg - weight_file: - name: yolov3-voc.weights - threshold: - value: 0.3 - detection_classes: - names: - - aeroplane - - bicycle - - bird - - boat - - bottle - - bus - - car - - cat - - chair - - cow - - diningtable - - dog - - horse - - motorbike - - person - - pottedplant - - sheep - - sofa - - train - - tvmonitor diff --git a/darknet_ros/config/yolov2.yaml b/darknet_ros/config/yolov4-csp.yaml similarity index 96% rename from darknet_ros/config/yolov2.yaml rename to darknet_ros/config/yolov4-csp.yaml index a6e4d67de..1f7243c19 100644 --- a/darknet_ros/config/yolov2.yaml +++ b/darknet_ros/config/yolov4-csp.yaml @@ -1,11 +1,10 @@ darknet_ros: ros__parameters: yolo_model: - config_file: - name: yolov2.cfg + name: yolov4-csp.cfg weight_file: - name: yolov2.weights + name: yolov4-csp.weights threshold: value: 0.3 detection_classes: diff --git a/darknet_ros/config/yolov4-tiny.yaml b/darknet_ros/config/yolov4-tiny.yaml new file mode 100644 index 000000000..287ccdbd6 --- /dev/null +++ b/darknet_ros/config/yolov4-tiny.yaml @@ -0,0 +1,91 @@ +darknet_ros: + ros__parameters: + yolo_model: + config_file: + name: yolov4-tiny.cfg + weight_file: + name: yolov4-tiny.weights + threshold: + value: 0.3 + detection_classes: + names: + - person + - bicycle + - car + - motorbike + - aeroplane + - bus + - train + - truck + - boat + - traffic light + - fire hydrant + - stop sign + - parking meter + - bench + - bird + - cat + - dog + - horse + - sheep + - cow + - elephant + - bear + - zebra + - giraffe + - backpack + - umbrella + - handbag + - tie + - suitcase + - frisbee + - skis + - snowboard + - sports ball + - kite + - baseball bat + - baseball glove + - skateboard + - surfboard + - tennis racket + - bottle + - wine glass + - cup + - fork + - knife + - spoon + - bowl + - banana + - apple + - sandwich + - orange + - broccoli + - carrot + - hot dog + - pizza + - donut + - cake + - chair + - sofa + - pottedplant + - bed + - diningtable + - toilet + - tvmonitor + - laptop + - mouse + - remote + - keyboard + - cell phone + - microwave + - oven + - toaster + - sink + - refrigerator + - book + - clock + - vase + - scissors + - teddy bear + - hair drier + - toothbrush \ No newline at end of file diff --git a/darknet_ros/config/yolov4.yaml b/darknet_ros/config/yolov4.yaml new file mode 100644 index 000000000..602a023ee --- /dev/null +++ b/darknet_ros/config/yolov4.yaml @@ -0,0 +1,91 @@ +darknet_ros: + ros__parameters: + yolo_model: + config_file: + name: yolov4.cfg + weight_file: + name: yolov4.weights + threshold: + value: 0.3 + detection_classes: + names: + - person + - bicycle + - car + - motorbike + - aeroplane + - bus + - train + - truck + - boat + - traffic light + - fire hydrant + - stop sign + - parking meter + - bench + - bird + - cat + - dog + - horse + - sheep + - cow + - elephant + - bear + - zebra + - giraffe + - backpack + - umbrella + - handbag + - tie + - suitcase + - frisbee + - skis + - snowboard + - sports ball + - kite + - baseball bat + - baseball glove + - skateboard + - surfboard + - tennis racket + - bottle + - wine glass + - cup + - fork + - knife + - spoon + - bowl + - banana + - apple + - sandwich + - orange + - broccoli + - carrot + - hot dog + - pizza + - donut + - cake + - chair + - sofa + - pottedplant + - bed + - diningtable + - toilet + - tvmonitor + - laptop + - mouse + - remote + - keyboard + - cell phone + - microwave + - oven + - toaster + - sink + - refrigerator + - book + - clock + - vase + - scissors + - teddy bear + - hair drier + - toothbrush \ No newline at end of file diff --git a/darknet_ros/config/yolov7-tiny.yaml b/darknet_ros/config/yolov7-tiny.yaml new file mode 100644 index 000000000..8696d0d82 --- /dev/null +++ b/darknet_ros/config/yolov7-tiny.yaml @@ -0,0 +1,92 @@ +darknet_ros: + ros__parameters: + yolo_model: + config_file: + name: yolov7-tiny.cfg + weight_file: + name: yolov7-tiny.weights + threshold: + value: 0.3 + window_name: YOLO V7 + detection_classes: + names: + - person + - bicycle + - car + - motorbike + - aeroplane + - bus + - train + - truck + - boat + - traffic light + - fire hydrant + - stop sign + - parking meter + - bench + - bird + - cat + - dog + - horse + - sheep + - cow + - elephant + - bear + - zebra + - giraffe + - backpack + - umbrella + - handbag + - tie + - suitcase + - frisbee + - skis + - snowboard + - sports ball + - kite + - baseball bat + - baseball glove + - skateboard + - surfboard + - tennis racket + - bottle + - wine glass + - cup + - fork + - knife + - spoon + - bowl + - banana + - apple + - sandwich + - orange + - broccoli + - carrot + - hot dog + - pizza + - donut + - cake + - chair + - sofa + - pottedplant + - bed + - diningtable + - toilet + - tvmonitor + - laptop + - mouse + - remote + - keyboard + - cell phone + - microwave + - oven + - toaster + - sink + - refrigerator + - book + - clock + - vase + - scissors + - teddy bear + - hair drier + - toothbrush \ No newline at end of file diff --git a/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp b/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp index 1314455df..2dcf5c207 100644 --- a/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp +++ b/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp @@ -17,6 +17,9 @@ #include #include #include +#include +#include +#include // ROS #include "rclcpp/rclcpp.hpp" @@ -53,13 +56,27 @@ extern "C" { #include "utils.h" #include "parser.h" #include "box.h" -#include "darknet_ros/image_interface.h" +#include "blas.h" +#include "image_opencv.h" + +#include "image.h" +// #include "demo.h" +#include "darknet.h" + +#include "image_interface.hpp" + +#define START_COUNT 100 + #include } -extern "C" void ipl_into_image(IplImage* src, image im); -extern "C" image ipl_to_image(IplImage* src); -extern "C" void show_image_cv(image p, const char *name, IplImage *disp); +extern "C" cv::Mat image_to_mat(image im); +extern "C" image mat_to_image(cv::Mat m); +// extern "C" void show_image(image p, const char* name); + +// extern "C" void draw_detections_cv_v3(mat_cv* show_img, detection *dets, int num, float thresh, char **names, image **alphabet, int classes, int ext_output); + +extern "C" void generate_image(image p, cv::Mat& disp); namespace darknet_ros { @@ -70,11 +87,10 @@ typedef struct int num, Class; } RosBox_; -typedef struct -{ - IplImage* image; +typedef struct { + cv::Mat image; std_msgs::msg::Header header; -} IplImageWithHeader_; +} CvMatWithHeader_; class YoloObjectDetector : public rclcpp::Node { @@ -181,14 +197,20 @@ class YoloObjectDetector : public rclcpp::Node image **demoAlphabet_; int demoClasses_; + std::string windowName_; + network *net_; std_msgs::msg::Header headerBuff_[3]; image buff_[3]; image buffLetter_[3]; int buffId_[3]; int buffIndex_ = 0; - IplImage * ipl_; + // IplImage * ipl_; + cv::Mat disp_; float fps_ = 0; + float max_fps = 0; + float min_fps = 10000; + std::stringstream ss_fps; float demoThresh_ = 0; float demoHier_ = .5; int running_ = 0; @@ -249,13 +271,15 @@ class YoloObjectDetector : public rclcpp::Node void yolo(); - IplImageWithHeader_ getIplImageWithHeader(); + // IplImageWithHeader_ getIplImageWithHeader(); + CvMatWithHeader_ getCvMatWithHeader(); bool getImageStatus(void); bool isNodeRunning(void); void *publishInThread(); + void generate_image_cp(image p, cv::Mat& disp); }; } /* namespace darknet_ros*/ diff --git a/darknet_ros/include/darknet_ros/image_interface.h b/darknet_ros/include/darknet_ros/image_interface.hpp similarity index 78% rename from darknet_ros/include/darknet_ros/image_interface.h rename to darknet_ros/include/darknet_ros/image_interface.hpp index 2aa1353a3..80ac09308 100644 --- a/darknet_ros/include/darknet_ros/image_interface.h +++ b/darknet_ros/include/darknet_ros/image_interface.hpp @@ -6,8 +6,8 @@ * Institute: ETH Zurich, Robotic Systems Lab */ -#ifndef IMAGE_INTERFACE_H -#define IMAGE_INTERFACE_H +#ifndef IMAGE_INTERFACE_HPP +#define IMAGE_INTERFACE_HPP #include "opencv2/highgui/highgui_c.h" #include "opencv2/imgproc/imgproc_c.h" @@ -17,6 +17,6 @@ static float get_pixel(image m, int x, int y, int c); image **load_alphabet_with_file(char *datafile); -void generate_image(image p, IplImage *disp); +void generate_image(image p, cv::Mat& disp); -#endif +#endif \ No newline at end of file diff --git a/darknet_ros/launch/darknet_ros.launch.py b/darknet_ros/launch/darknet_ros.launch.py index 0cd39ecb2..39a82a69a 100644 --- a/darknet_ros/launch/darknet_ros.launch.py +++ b/darknet_ros/launch/darknet_ros.launch.py @@ -11,20 +11,20 @@ def generate_launch_description(): darknet_ros_share_dir = get_package_share_directory('darknet_ros') - image = LaunchConfiguration('image', default = '/camera/rgb/image_raw') + image = LaunchConfiguration('image', default = 'image_raw') yolo_weights_path = LaunchConfiguration('yolo_weights_path', default = darknet_ros_share_dir + '/yolo_network_config/weights') yolo_config_path = LaunchConfiguration('yolo_config_path', default = darknet_ros_share_dir + '/yolo_network_config/cfg') ros_param_file = LaunchConfiguration('ros_param_file', default = darknet_ros_share_dir + 'config/ros.yaml') - network_param_file = LaunchConfiguration('network_param_file', default = darknet_ros_share_dir + 'config/yolov2-tiny.yaml') + network_param_file = LaunchConfiguration('network_param_file', default = darknet_ros_share_dir + 'config/yolov4-tiny.yaml') declare_image_cmd = DeclareLaunchArgument( 'image', - default_value = '/camera/rgb/image_raw', + default_value = 'image_raw', description = 'Image topic') declare_yolo_weights_path_cmd = DeclareLaunchArgument( 'yolo_weights_path', default_value = darknet_ros_share_dir + '/yolo_network_config/weights', - description = 'Path to yolo weights') + description = 'Path to yolo weights') declare_yolo_config_path_cmd = DeclareLaunchArgument( 'yolo_config_path', default_value = darknet_ros_share_dir + '/yolo_network_config/cfg', @@ -35,13 +35,13 @@ def generate_launch_description(): description = 'Path to file with ROS related config') declare_network_param_file_cmd = DeclareLaunchArgument( 'network_param_file', - default_value = darknet_ros_share_dir + '/config/yolov2-tiny.yaml', - description = 'Path to file with network param file') + default_value = darknet_ros_share_dir + '/config/yolov4-tiny.yaml', + description = 'Path to file with network param file') darknet_ros_cmd = Node( package='darknet_ros', - node_executable='darknet_ros', - node_name='darknet_ros', + executable='darknet_ros', + name='darknet_ros', output='screen', parameters=[ros_param_file, network_param_file, { @@ -60,4 +60,4 @@ def generate_launch_description(): ld.add_action(darknet_ros_cmd) - return ld + return ld \ No newline at end of file diff --git a/darknet_ros/launch/yolov4-csp.launch.py b/darknet_ros/launch/yolov4-csp.launch.py new file mode 100644 index 000000000..6d5eec347 --- /dev/null +++ b/darknet_ros/launch/yolov4-csp.launch.py @@ -0,0 +1,27 @@ +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch_ros.actions import Node + +def generate_launch_description(): + darknet_ros_share_dir = get_package_share_directory('darknet_ros') + network_param_file = darknet_ros_share_dir + '/config/yolov4-csp.yaml' + + darknet_ros_launch = IncludeLaunchDescription( + PythonLaunchDescriptionSource([darknet_ros_share_dir + '/launch/darknet_ros.launch.py']), + launch_arguments={'network_param_file': network_param_file}.items() + ) + + camera = Node( + package="v4l2_camera", + executable="v4l2_camera_node", + parameters=[ + {'video_device' : "/dev/video0"}, + ]) + + return LaunchDescription([ + darknet_ros_launch, + # if you want to disable camera node, remove the following line. + camera, + ]) \ No newline at end of file diff --git a/darknet_ros/launch/yolov4-tiny.launch.py b/darknet_ros/launch/yolov4-tiny.launch.py new file mode 100644 index 000000000..69a42fdeb --- /dev/null +++ b/darknet_ros/launch/yolov4-tiny.launch.py @@ -0,0 +1,27 @@ +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch_ros.actions import Node + +def generate_launch_description(): + darknet_ros_share_dir = get_package_share_directory('darknet_ros') + network_param_file = darknet_ros_share_dir + '/config/yolov4-tiny.yaml' + + darknet_ros_launch = IncludeLaunchDescription( + PythonLaunchDescriptionSource([darknet_ros_share_dir + '/launch/darknet_ros.launch.py']), + launch_arguments={'network_param_file': network_param_file}.items() + ) + + camera = Node( + package="v4l2_camera", + executable="v4l2_camera_node", + parameters=[ + {'video_device' : "/dev/video0"}, + ]) + + return LaunchDescription([ + darknet_ros_launch, + # if you want to disable camera node, remove the following line. + camera, + ]) \ No newline at end of file diff --git a/darknet_ros/launch/yolov7-tiny.launch.py b/darknet_ros/launch/yolov7-tiny.launch.py new file mode 100644 index 000000000..e38bb3e94 --- /dev/null +++ b/darknet_ros/launch/yolov7-tiny.launch.py @@ -0,0 +1,27 @@ +from ament_index_python.packages import get_package_share_directory +from launch import LaunchDescription +from launch.actions import IncludeLaunchDescription +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch_ros.actions import Node + +def generate_launch_description(): + darknet_ros_share_dir = get_package_share_directory('darknet_ros') + network_param_file = darknet_ros_share_dir + '/config/yolov7-tiny.yaml' + + darknet_ros_launch = IncludeLaunchDescription( + PythonLaunchDescriptionSource([darknet_ros_share_dir + '/launch/darknet_ros.launch.py']), + launch_arguments={'network_param_file': network_param_file}.items() + ) + + camera = Node( + package="v4l2_camera", + executable="v4l2_camera_node", + parameters=[ + {'video_device' : "/dev/video0"}, + ]) + + return LaunchDescription([ + darknet_ros_launch, + # if you want to disable camera node, remove the following line. + camera, + ]) diff --git a/darknet_ros/package.xml b/darknet_ros/package.xml index 9df4490f7..919d291d0 100644 --- a/darknet_ros/package.xml +++ b/darknet_ros/package.xml @@ -2,7 +2,7 @@ darknet_ros - 1.1.4 + 1.1.5 Darknet is an open source neural network framework that runs on CPU and GPU. You only look once (YOLO) is a state-of-the-art, real-time object detection system. Marko Bjelonic BSD diff --git a/darknet_ros/src/YoloObjectDetector.cpp b/darknet_ros/src/YoloObjectDetector.cpp index 67d5c3b41..53bd053fd 100644 --- a/darknet_ros/src/YoloObjectDetector.cpp +++ b/darknet_ros/src/YoloObjectDetector.cpp @@ -59,6 +59,7 @@ YoloObjectDetector::YoloObjectDetector() declare_parameter("publishers.detection_image.topic", std::string("detection_image")); declare_parameter("publishers.detection_image.queue_size", 1); declare_parameter("publishers.detection_image.latch", true); + declare_parameter("yolo_model.window_name", std::string("YOLO")); declare_parameter("actions.camera_reading.topic", std::string("check_for_objects")); } @@ -79,6 +80,8 @@ bool YoloObjectDetector::readParameters() get_parameter("image_view.wait_key_delay", waitKeyDelay_); get_parameter("image_view.enable_console_output", enableConsoleOutput_); + get_parameter("yolo_model.window_name", windowName_); + // Check if Xserver is running on Linux. if (XOpenDisplay(NULL)) { // Do nothing! @@ -321,15 +324,6 @@ bool YoloObjectDetector::publishDetectionImage(const cv::Mat& detectionImage) return true; } -// double YoloObjectDetector::getWallTime() -// { -// struct timeval time; -// if (gettimeofday(&time, NULL)) { -// return 0; -// } -// return (double) time.tv_sec + (double) time.tv_usec * .000001; -// } - int YoloObjectDetector::sizeNetwork(network *net) { int i; @@ -371,7 +365,8 @@ detection *YoloObjectDetector::avgPredictions(network *net, int *nboxes) count += l.outputs; } } - detection *dets = get_network_boxes(net, buff_[0].w, buff_[0].h, demoThresh_, demoHier_, 0, 1, nboxes); + // detection *dets = get_network_boxes(net, buff_[0].w, buff_[0].h, demoThresh_, demoHier_, 0, 1, nboxes); + detection *dets = get_network_boxes(net, buff_[0].w, buff_[0].h, demoThresh_, demoHier_, 0, 1, nboxes, 1); // letter box return dets; } @@ -379,10 +374,11 @@ void *YoloObjectDetector::detectInThread() { running_ = 1; float nms = .4; + // mat_cv* show_img = NULL; layer l = net_->layers[net_->n - 1]; float *X = buffLetter_[(buffIndex_ + 2) % 3].data; - float *prediction = network_predict(net_, X); + float *prediction = network_predict(*net_, X); rememberNetwork(net_); detection *dets = 0; @@ -394,12 +390,13 @@ void *YoloObjectDetector::detectInThread() if (enableConsoleOutput_) { printf("\033[2J"); printf("\033[1;1H"); - printf("\nFPS:%.1f\n",fps_); + printf("\nFPS:%.1f : ( %s )\n",fps_,ss_fps.str().c_str()); printf("Objects:\n\n"); } image display = buff_[(buffIndex_+2) % 3]; - draw_detections(display, dets, nboxes, demoThresh_, demoNames_, demoAlphabet_, demoClasses_); - + // draw_detections(display, dets, nboxes, demoThresh_, demoNames_, demoAlphabet_, demoClasses_); + + draw_detections_v3(display, dets, nboxes, demoThresh_, demoNames_, demoAlphabet_, demoClasses_, 1); // extract the bounding boxes and send them to ROS int i, j; int count = 0; @@ -455,32 +452,12 @@ void *YoloObjectDetector::detectInThread() return 0; } - -void ipl_into_image_cp(IplImage* src, image im) -{ - unsigned char *data = (unsigned char *)src->imageData; - int h = src->height; - int w = src->width; - int c = src->nChannels; - int step = src->widthStep; - int i, j, k; - - for(i = 0; i < h; ++i){ - for(k= 0; k < c; ++k){ - for(j = 0; j < w; ++j){ - im.data[k*w*h + i*w + j] = data[i*step + j*c + k]/255.; - } - } - } -} - -void *YoloObjectDetector::fetchInThread() -{ +void* YoloObjectDetector::fetchInThread() { { std::shared_lock lock(mutexImageCallback_); - IplImageWithHeader_ imageAndHeader = getIplImageWithHeader(); - IplImage* ROS_img = imageAndHeader.image; - ipl_into_image_cp(ROS_img, buff_[buffIndex_]); + CvMatWithHeader_ imageAndHeader = getCvMatWithHeader(); + free_image(buff_[buffIndex_]); + buff_[buffIndex_] = mat_to_image(imageAndHeader.image); headerBuff_[buffIndex_] = imageAndHeader.header; buffId_[buffIndex_] = actionId_; } @@ -498,64 +475,28 @@ float get_pixel_cp(image m, int x, int y, int c) int windows = 0; -void show_image_cv_cp(image p, const char *name, IplImage *disp) -{ - int x,y,k; - if(p.c == 3) rgbgr_image(p); - //normalize_image(copy); - - char buff[256]; - //sprintf(buff, "%s (%d)", name, windows); - sprintf(buff, "%s", name); - - int step = disp->widthStep; - cvNamedWindow(buff, CV_WINDOW_NORMAL); - //cvMoveWindow(buff, 100*(windows%10) + 200*(windows/10), 100*(windows%10)); - ++windows; - for(y = 0; y < p.h; ++y){ - for(x = 0; x < p.w; ++x){ - for(k= 0; k < p.c; ++k){ - disp->imageData[y*step + x*p.c + k] = (unsigned char)(get_pixel_cp(p,x,y,k)*255); - } - } - } - if(0){ - int w = 448; - int h = w*p.h/p.w; - if(h > 1000){ - h = 1000; - w = h*p.w/p.h; - } - IplImage *buffer = disp; - disp = cvCreateImage(cvSize(w, h), buffer->depth, buffer->nChannels); - cvResize(buffer, disp, CV_INTER_LINEAR); - cvReleaseImage(&buffer); - } - cvShowImage(buff, disp); -} - -void *YoloObjectDetector::displayInThread(void *ptr) -{ - show_image_cv_cp(buff_[(buffIndex_ + 1)%3], "YOLO V3", ipl_); +void* YoloObjectDetector::displayInThread(void* ptr) { + show_image_cv(buff_[(buffIndex_ + 1) % 3], windowName_.c_str()); int c = cv::waitKey(waitKeyDelay_); - if (c != -1) c = c%256; + if (c != -1) c = c % 256; if (c == 27) { - demoDone_ = 1; - return 0; + demoDone_ = 1; + return 0; } else if (c == 82) { - demoThresh_ += .02; + demoThresh_ += .02; } else if (c == 84) { - demoThresh_ -= .02; - if(demoThresh_ <= .02) demoThresh_ = .02; + demoThresh_ -= .02; + if (demoThresh_ <= .02) demoThresh_ = .02; } else if (c == 83) { - demoHier_ += .02; + demoHier_ += .02; } else if (c == 81) { - demoHier_ -= .02; - if(demoHier_ <= .0) demoHier_ = .0; + demoHier_ -= .02; + if (demoHier_ <= .0) demoHier_ = .0; } return 0; } + void *YoloObjectDetector::displayLoop(void *ptr) { while (1) { @@ -610,34 +551,9 @@ void YoloObjectDetector::setupNetwork(char *cfgfile, char *weightfile, char *dat set_batch_network(net_, 1); } -void generate_image_cp(image p, IplImage *disp) -{ - int x,y,k; - if(p.c == 3) rgbgr_image(p); - //normalize_image(copy); - - int step = disp->widthStep; - for(y = 0; y < p.h; ++y){ - for(x = 0; x < p.w; ++x){ - for(k= 0; k < p.c; ++k){ - disp->imageData[y*step + x*p.c + k] = (unsigned char)(get_pixel_cp(p,x,y,k)*255); - } - } - } -} - -image ipl_to_image_cp(IplImage* src) -{ - int h = src->height; - int w = src->width; - int c = src->nChannels; - image out = make_image(w, h, c); - ipl_into_image_cp(src, out); - return out; -} - void YoloObjectDetector::yolo() { + static int start_count = 0; const auto wait_duration = std::chrono::milliseconds(2000); while (!getImageStatus()) { printf("Waiting for image.\n"); @@ -665,9 +581,8 @@ void YoloObjectDetector::yolo() { std::shared_lock lock(mutexImageCallback_); - IplImageWithHeader_ imageAndHeader = getIplImageWithHeader(); - IplImage* ROS_img = imageAndHeader.image; - buff_[0] = ipl_to_image_cp(ROS_img); + CvMatWithHeader_ imageAndHeader = getCvMatWithHeader(); + buff_[0] = mat_to_image(imageAndHeader.image); headerBuff_[0] = imageAndHeader.header; } buff_[1] = copy_image(buff_[0]); @@ -677,17 +592,17 @@ void YoloObjectDetector::yolo() buffLetter_[0] = letterbox_image(buff_[0], net_->w, net_->h); buffLetter_[1] = letterbox_image(buff_[0], net_->w, net_->h); buffLetter_[2] = letterbox_image(buff_[0], net_->w, net_->h); - ipl_ = cvCreateImage(cvSize(buff_[0].w, buff_[0].h), IPL_DEPTH_8U, buff_[0].c); + // buff_[0] = mat_to_image(imageAndHeader.image); + disp_ = image_to_mat(buff_[0]); int count = 0; - if (!demoPrefix_ && viewImage_) { - cv::namedWindow("YOLO V3", cv::WINDOW_NORMAL); + cv::namedWindow(windowName_.c_str(), cv::WINDOW_NORMAL); if (fullScreen_) { - cv::setWindowProperty("YOLO V3", cv::WND_PROP_FULLSCREEN, cv::WINDOW_FULLSCREEN); + cv::setWindowProperty(windowName_.c_str(), cv::WND_PROP_FULLSCREEN, cv::WINDOW_FULLSCREEN); } else { - cv::moveWindow("YOLO V3", 0, 0); - cv::resizeWindow("YOLO V3", 640, 480); + cv::moveWindow(windowName_.c_str(), 0, 0); + cv::resizeWindow(windowName_.c_str(), 640, 480); } } @@ -699,11 +614,24 @@ void YoloObjectDetector::yolo() detect_thread = std::thread(&YoloObjectDetector::detectInThread, this); if (!demoPrefix_) { fps_ = 1./(what_time_is_it_now() - demoTime_); + + if (start_count > START_COUNT) { + if (fps_ > max_fps) + max_fps = fps_; + else if (fps_ < min_fps) + min_fps = fps_; + } + else + start_count++; + + ss_fps.str(""); + ss_fps << "MAX:" << max_fps << " MIN:" << min_fps; + demoTime_ = what_time_is_it_now(); if (viewImage_) { displayInThread(0); } else { - generate_image_cp(buff_[(buffIndex_ + 1)%3], ipl_); + generate_image_cp(buff_[(buffIndex_ + 1)%3], disp_); } publishInThread(); } else { @@ -718,14 +646,10 @@ void YoloObjectDetector::yolo() demoDone_ = true; } } - } -IplImageWithHeader_ YoloObjectDetector::getIplImageWithHeader() -{ - IplImage* ROS_img = new IplImage(); - *ROS_img = cvIplImage(camImageCopy_); - IplImageWithHeader_ header = {.image = ROS_img, .header = imageHeader_}; +CvMatWithHeader_ YoloObjectDetector::getCvMatWithHeader() { + CvMatWithHeader_ header = {.image = camImageCopy_, .header = imageHeader_}; return header; } @@ -744,7 +668,8 @@ bool YoloObjectDetector::isNodeRunning(void) void *YoloObjectDetector::publishInThread() { // Publish image. - cv::Mat cvImage = cv::cvarrToMat(ipl_); + // cv::Mat cvImage = cv::cvarrToMat(ipl_); + cv::Mat cvImage = disp_; if (!publishDetectionImage(cv::Mat(cvImage))) { RCLCPP_DEBUG(get_logger(), "Detection image has not been broadcasted."); } @@ -817,5 +742,19 @@ void *YoloObjectDetector::publishInThread() return 0; } +void YoloObjectDetector::generate_image_cp(image p, cv::Mat& disp) { + int x, y, k; + if (p.c == 3) rgbgr_image(p); + // normalize_image(copy); + + int step = disp.step; + for (y = 0; y < p.h; ++y) { + for (x = 0; x < p.w; ++x) { + for (k = 0; k < p.c; ++k) { + disp.data[y * step + x * p.c + k] = (unsigned char)(get_pixel_cp(p, x, y, k) * 255); + } + } + } +} } /* namespace darknet_ros*/ diff --git a/darknet_ros/src/image_interface.c b/darknet_ros/src/image_interface.cpp similarity index 67% rename from darknet_ros/src/image_interface.c rename to darknet_ros/src/image_interface.cpp index 8ee77cd43..a59d1875d 100644 --- a/darknet_ros/src/image_interface.c +++ b/darknet_ros/src/image_interface.cpp @@ -6,7 +6,7 @@ * Institute: ETH Zurich, Robotic Systems Lab */ -#include "darknet_ros/image_interface.h" +#include "darknet_ros/image_interface.hpp" static float get_pixel(image m, int x, int y, int c) { @@ -34,19 +34,18 @@ image **load_alphabet_with_file(char *datafile) { } #ifdef OPENCV -void generate_image(image p, IplImage *disp) -{ - int x,y,k; - if(p.c == 3) rgbgr_image(p); - //normalize_image(copy); +void generate_image(image p, cv::Mat& disp) { + int x, y, k; + if (p.c == 3) rgbgr_image(p); + // normalize_image(copy); - int step = disp->widthStep; - for(y = 0; y < p.h; ++y){ - for(x = 0; x < p.w; ++x){ - for(k= 0; k < p.c; ++k){ - disp->imageData[y*step + x*p.c + k] = (unsigned char)(get_pixel(p,x,y,k)*255); - } - } + int step = disp.step; + for (y = 0; y < p.h; ++y) { + for (x = 0; x < p.w; ++x) { + for (k = 0; k < p.c; ++k) { + disp.data[y * step + x * p.c + k] = (unsigned char)(get_pixel(p, x, y, k) * 255); + } } + } } #endif diff --git a/darknet_ros/test/ObjectDetection.cpp b/darknet_ros/test/ObjectDetection.cpp index 3ac9a74ee..69c351d3b 100644 --- a/darknet_ros/test/ObjectDetection.cpp +++ b/darknet_ros/test/ObjectDetection.cpp @@ -6,7 +6,6 @@ * Institute: ETH Zurich, Robotic Systems Lab */ - // Google Test #include @@ -14,24 +13,23 @@ #include "rclcpp/rclcpp.hpp" #include "ament_index_cpp/get_package_share_directory.hpp" #include -#include // OpenCV2. +#include #include #include #include -#include // Actions. #include -typedef actionlib::SimpleActionClient CheckForObjectsActionClient; -typedef std::shared_ptr CheckForObjectsActionClientPtr; +using CheckForObjectsActionClient = actionlib::SimpleActionClient; +using CheckForObjectsActionClientPtr = std::shared_ptr; // c++ -#include #include +#include #ifdef DARKNET_FILE_PATH std::string darknetFilePath_ = DARKNET_FILE_PATH; @@ -46,35 +44,30 @@ darknet_ros_msgs::BoundingBoxes boundingBoxesResults_; * @param[in] state * @param[in] result */ -void checkForObjectsResultCB( - const actionlib::SimpleClientGoalState& state, - const darknet_ros_msgs::CheckForObjectsResultConstPtr& result) { - std::cout << "[ObjectDetectionTest] Received bounding boxes." << std::endl; +void checkForObjectsResultCB(const actionlib::SimpleClientGoalState& state, const darknet_ros_msgs::CheckForObjectsResultConstPtr& result) { + std::cout << "[ObjectDetectionTest] Received bounding boxes." << std::endl; boundingBoxesResults_ = result->bounding_boxes; } bool sendImageToYolo(ros::NodeHandle nh, const std::string& pathToTestImage) { - //!Check for objects action client. + //! Check for objects action client. CheckForObjectsActionClientPtr checkForObjectsActionClient; // Action clients. std::string checkForObjectsActionName; nh.param("/darknet_ros/camera_action", checkForObjectsActionName, std::string("/darknet_ros/check_for_objects")); - checkForObjectsActionClient.reset( - new CheckForObjectsActionClient( - nh, checkForObjectsActionName, - true)); + checkForObjectsActionClient.reset(new CheckForObjectsActionClient(nh, checkForObjectsActionName, true)); // Wait till action server launches. - if(!checkForObjectsActionClient->waitForServer(ros::Duration(20.0))) { - std::cout << "[ObjectDetectionTest] sendImageToYolo(): checkForObjects action server has not been advertised." << std::endl; - return false; + if (!checkForObjectsActionClient->waitForServer(ros::Duration(20.0))) { + std::cout << "[ObjectDetectionTest] sendImageToYolo(): checkForObjects action server has not been advertised." << std::endl; + return false; } // Get test image cv_bridge::CvImagePtr cv_ptr(new cv_bridge::CvImage); - cv_ptr->image = cv::imread(pathToTestImage, CV_LOAD_IMAGE_COLOR); + cv_ptr->image = cv::imread(pathToTestImage, cv::IMREAD_COLOR); cv_ptr->encoding = sensor_msgs::image_encodings::RGB8; sensor_msgs::ImagePtr image = cv_ptr->toImageMsg(); @@ -84,24 +77,21 @@ bool sendImageToYolo(ros::NodeHandle nh, const std::string& pathToTestImage) { // Send goal. ros::Time beginYolo = ros::Time::now(); - checkForObjectsActionClient->sendGoal( - goal, - boost::bind(&checkForObjectsResultCB, _1, _2), - CheckForObjectsActionClient::SimpleActiveCallback(), - CheckForObjectsActionClient::SimpleFeedbackCallback()); + checkForObjectsActionClient->sendGoal(goal, boost::bind(&checkForObjectsResultCB, _1, _2), + CheckForObjectsActionClient::SimpleActiveCallback(), + CheckForObjectsActionClient::SimpleFeedbackCallback()); - if(!checkForObjectsActionClient->waitForResult(ros::Duration(100.0))) { + if (!checkForObjectsActionClient->waitForResult(ros::Duration(100.0))) { std::cout << "[ObjectDetectionTest] sendImageToYolo(): checkForObjects action server took to long to send back result." << std::endl; return false; } ros::Time endYolo = ros::Time::now(); - std::cout << "[ObjectDetectionTest] Object detection for one image took " << endYolo-beginYolo << " seconds." << std::endl; + std::cout << "[ObjectDetectionTest] Object detection for one image took " << endYolo - beginYolo << " seconds." << std::endl; return true; } -TEST(ObjectDetection, DISABLED_DetectDog) -{ - srand((unsigned int) time(0)); +TEST(ObjectDetection, DISABLED_DetectDog) { + srand(static_cast(time(nullptr))); ros::NodeHandle nodeHandle("~"); // Path to test image. @@ -122,25 +112,23 @@ TEST(ObjectDetection, DISABLED_DetectDog) bool detectedCar = false; double centerErrorCar; - for(unsigned int i = 0; i < boundingBoxesResults_.bounding_boxes.size(); ++i) { - double xPosCenter = boundingBoxesResults_.bounding_boxes.at(i).xmin + - (boundingBoxesResults_.bounding_boxes.at(i).xmax - boundingBoxesResults_.bounding_boxes.at(i).xmin)*0.5; - double yPosCenter = boundingBoxesResults_.bounding_boxes.at(i).ymin + - (boundingBoxesResults_.bounding_boxes.at(i).ymax - boundingBoxesResults_.bounding_boxes.at(i).ymin)*0.5; + for (auto& boundingBox : boundingBoxesResults_.bounding_boxes) { + double xPosCenter = boundingBox.xmin + (boundingBox.xmax - boundingBox.xmin) * 0.5; + double yPosCenter = boundingBox.ymin + (boundingBox.ymax - boundingBox.ymin) * 0.5; - if(boundingBoxesResults_.bounding_boxes.at(i).Class == "dog") { + if (boundingBox.Class == "dog") { detectedDog = true; - //std::cout << "centerErrorDog " << xPosCenter << ", " << yPosCenter << std::endl; + // std::cout << "centerErrorDog " << xPosCenter << ", " << yPosCenter << std::endl; centerErrorDog = std::sqrt(std::pow(xPosCenter - 222.5, 2) + std::pow(yPosCenter - 361.5, 2)); } - if(boundingBoxesResults_.bounding_boxes.at(i).Class == "bicycle") { + if (boundingBox.Class == "bicycle") { detectedBicycle = true; - //std::cout << "centerErrorBicycle " << xPosCenter << ", " << yPosCenter << std::endl; + // std::cout << "centerErrorBicycle " << xPosCenter << ", " << yPosCenter << std::endl; centerErrorBicycle = std::sqrt(std::pow(xPosCenter - 338.0, 2) + std::pow(yPosCenter - 289.0, 2)); } - if(boundingBoxesResults_.bounding_boxes.at(i).Class == "truck") { + if (boundingBox.Class == "truck") { detectedCar = true; - //std::cout << "centerErrorCar " << xPosCenter << ", " << yPosCenter << std::endl; + // std::cout << "centerErrorCar " << xPosCenter << ", " << yPosCenter << std::endl; centerErrorCar = std::sqrt(std::pow(xPosCenter - 561.0, 2) + std::pow(yPosCenter - 126.5, 2)); } } @@ -153,9 +141,8 @@ TEST(ObjectDetection, DISABLED_DetectDog) EXPECT_LT(centerErrorCar, 40.0); } -TEST(ObjectDetection, DetectANYmal) -{ - srand((unsigned int) time(0)); +TEST(ObjectDetection, DetectANYmal) { + srand(static_cast(time(nullptr))); ros::NodeHandle nodeHandle("~"); // Path to test image. @@ -164,7 +151,8 @@ TEST(ObjectDetection, DetectANYmal) pathToTestImage += "quadruped_anymal_and_person"; pathToTestImage += ".JPG"; - // Send dog image to yolo. + // Send ANYmal and person image to yolo. + ASSERT_TRUE(sendImageToYolo(nodeHandle, pathToTestImage)); ASSERT_TRUE(sendImageToYolo(nodeHandle, pathToTestImage)); ASSERT_TRUE(sendImageToYolo(nodeHandle, pathToTestImage)); @@ -173,13 +161,11 @@ TEST(ObjectDetection, DetectANYmal) double centerErrorPersonX; double centerErrorPersonY; - for(unsigned int i = 0; i < boundingBoxesResults_.bounding_boxes.size(); ++i) { - double xPosCenter = boundingBoxesResults_.bounding_boxes.at(i).xmin + - (boundingBoxesResults_.bounding_boxes.at(i).xmax - boundingBoxesResults_.bounding_boxes.at(i).xmin)*0.5; - double yPosCenter = boundingBoxesResults_.bounding_boxes.at(i).ymin + - (boundingBoxesResults_.bounding_boxes.at(i).ymax - boundingBoxesResults_.bounding_boxes.at(i).ymin)*0.5; + for (auto& boundingBox : boundingBoxesResults_.bounding_boxes) { + double xPosCenter = boundingBox.xmin + (boundingBox.xmax - boundingBox.xmin) * 0.5; + double yPosCenter = boundingBox.ymin + (boundingBox.ymax - boundingBox.ymin) * 0.5; - if(boundingBoxesResults_.bounding_boxes.at(i).Class == "person") { + if (boundingBox.Class == "person") { detectedPerson = true; centerErrorPersonX = std::sqrt(std::pow(xPosCenter - 1650.0, 2)); centerErrorPersonY = std::sqrt(std::pow(xPosCenter - 1675.0, 2)); @@ -192,7 +178,7 @@ TEST(ObjectDetection, DetectANYmal) } TEST(ObjectDetection, DISABLED_DetectPerson) { - srand((unsigned int) time(0)); + srand(static_cast(time(nullptr))); ros::NodeHandle nodeHandle("~"); // Path to test image. @@ -208,15 +194,13 @@ TEST(ObjectDetection, DISABLED_DetectPerson) { bool detectedPerson = false; double centerErrorPerson; - for(unsigned int i = 0; i < boundingBoxesResults_.bounding_boxes.size(); ++i) { - double xPosCenter = boundingBoxesResults_.bounding_boxes.at(i).xmin + - (boundingBoxesResults_.bounding_boxes.at(i).xmax - boundingBoxesResults_.bounding_boxes.at(i).xmin)*0.5; - double yPosCenter = boundingBoxesResults_.bounding_boxes.at(i).ymin + - (boundingBoxesResults_.bounding_boxes.at(i).ymax - boundingBoxesResults_.bounding_boxes.at(i).ymin)*0.5; + for (auto& boundingBox : boundingBoxesResults_.bounding_boxes) { + double xPosCenter = boundingBox.xmin + (boundingBox.xmax - boundingBox.xmin) * 0.5; + double yPosCenter = boundingBox.ymin + (boundingBox.ymax - boundingBox.ymin) * 0.5; - if(boundingBoxesResults_.bounding_boxes.at(i).Class == "person") { + if (boundingBox.Class == "person") { detectedPerson = true; - //std::cout << "centerErrorPerson " << xPosCenter << ", " << yPosCenter << std::endl; + // std::cout << "centerErrorPerson " << xPosCenter << ", " << yPosCenter << std::endl; centerErrorPerson = std::sqrt(std::pow(xPosCenter - 228.0, 2) + std::pow(yPosCenter - 238.0, 2)); } } diff --git a/darknet_ros/test/test_main.cpp b/darknet_ros/test/test_main.cpp index 8292d40ee..e43bbae05 100644 --- a/darknet_ros/test/test_main.cpp +++ b/darknet_ros/test/test_main.cpp @@ -4,7 +4,7 @@ #include int main(int argc, char** argv) { - ros::init(argc, argv, "darknet_ros_test"); - testing::InitGoogleTest(&argc, argv); - return RUN_ALL_TESTS(); + ros::init(argc, argv, "darknet_ros_test"); + testing::InitGoogleTest(&argc, argv); + return RUN_ALL_TESTS(); } diff --git a/darknet_ros/yolo_network_config/cfg/yolov2-tiny-voc.cfg b/darknet_ros/yolo_network_config/cfg/yolov2-tiny-voc.cfg deleted file mode 100644 index c4c127cdd..000000000 --- a/darknet_ros/yolo_network_config/cfg/yolov2-tiny-voc.cfg +++ /dev/null @@ -1,138 +0,0 @@ -[net] -# Testing -batch=1 -subdivisions=1 -# Training -# batch=64 -# subdivisions=2 -width=416 -height=416 -channels=3 -momentum=0.9 -decay=0.0005 -angle=0 -saturation = 1.5 -exposure = 1.5 -hue=.1 - -learning_rate=0.001 -max_batches = 40200 -policy=steps -steps=-1,100,20000,30000 -scales=.1,10,.1,.1 - -[convolutional] -batch_normalize=1 -filters=16 -size=3 -stride=1 -pad=1 -activation=leaky - -[maxpool] -size=2 -stride=2 - -[convolutional] -batch_normalize=1 -filters=32 -size=3 -stride=1 -pad=1 -activation=leaky - -[maxpool] -size=2 -stride=2 - -[convolutional] -batch_normalize=1 -filters=64 -size=3 -stride=1 -pad=1 -activation=leaky - -[maxpool] -size=2 -stride=2 - -[convolutional] -batch_normalize=1 -filters=128 -size=3 -stride=1 -pad=1 -activation=leaky - -[maxpool] -size=2 -stride=2 - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky - -[maxpool] -size=2 -stride=2 - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[maxpool] -size=2 -stride=1 - -[convolutional] -batch_normalize=1 -filters=1024 -size=3 -stride=1 -pad=1 -activation=leaky - -########### - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=1024 -activation=leaky - -[convolutional] -size=1 -stride=1 -pad=1 -filters=125 -activation=linear - -[region] -anchors = 1.08,1.19, 3.42,4.41, 6.63,11.38, 9.42,5.11, 16.62,10.52 -bias_match=1 -classes=20 -coords=4 -num=5 -softmax=1 -jitter=.2 -rescore=1 - -object_scale=5 -noobject_scale=1 -class_scale=1 -coord_scale=1 - -absolute=1 -thresh = .6 -random=1 diff --git a/darknet_ros/yolo_network_config/cfg/yolov2-voc.cfg b/darknet_ros/yolo_network_config/cfg/yolov2-voc.cfg deleted file mode 100644 index dbf2de281..000000000 --- a/darknet_ros/yolo_network_config/cfg/yolov2-voc.cfg +++ /dev/null @@ -1,258 +0,0 @@ -[net] -# Testing -batch=1 -subdivisions=1 -# Training -# batch=64 -# subdivisions=8 -height=416 -width=416 -channels=3 -momentum=0.9 -decay=0.0005 -angle=0 -saturation = 1.5 -exposure = 1.5 -hue=.1 - -learning_rate=0.001 -burn_in=1000 -max_batches = 80200 -policy=steps -steps=40000,60000 -scales=.1,.1 - -[convolutional] -batch_normalize=1 -filters=32 -size=3 -stride=1 -pad=1 -activation=leaky - -[maxpool] -size=2 -stride=2 - -[convolutional] -batch_normalize=1 -filters=64 -size=3 -stride=1 -pad=1 -activation=leaky - -[maxpool] -size=2 -stride=2 - -[convolutional] -batch_normalize=1 -filters=128 -size=3 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=64 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=128 -size=3 -stride=1 -pad=1 -activation=leaky - -[maxpool] -size=2 -stride=2 - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky - -[maxpool] -size=2 -stride=2 - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[maxpool] -size=2 -stride=2 - -[convolutional] -batch_normalize=1 -filters=1024 -size=3 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=1024 -size=3 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=1024 -size=3 -stride=1 -pad=1 -activation=leaky - - -####### - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=1024 -activation=leaky - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=1024 -activation=leaky - -[route] -layers=-9 - -[convolutional] -batch_normalize=1 -size=1 -stride=1 -pad=1 -filters=64 -activation=leaky - -[reorg] -stride=2 - -[route] -layers=-1,-4 - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=1024 -activation=leaky - -[convolutional] -size=1 -stride=1 -pad=1 -filters=125 -activation=linear - - -[region] -anchors = 1.3221, 1.73145, 3.19275, 4.00944, 5.05587, 8.09892, 9.47112, 4.84053, 11.2364, 10.0071 -bias_match=1 -classes=20 -coords=4 -num=5 -softmax=1 -jitter=.3 -rescore=1 - -object_scale=5 -noobject_scale=1 -class_scale=1 -coord_scale=1 - -absolute=1 -thresh = .6 -random=1 diff --git a/darknet_ros/yolo_network_config/cfg/yolov4-csp.cfg b/darknet_ros/yolo_network_config/cfg/yolov4-csp.cfg new file mode 100644 index 000000000..55d97e155 --- /dev/null +++ b/darknet_ros/yolo_network_config/cfg/yolov4-csp.cfg @@ -0,0 +1,1280 @@ +[net] +# Testing +#batch=1 +#subdivisions=1 +# Training +batch=1 +subdivisions=1 +width=512 +height=512 +channels=3 +momentum=0.949 +decay=0.0005 +angle=0 +saturation = 1.5 +exposure = 1.5 +hue=.1 + + +learning_rate=0.001 +burn_in=1000 +max_batches = 500500 +policy=steps +steps=400000,450000 +scales=.1,.1 + +mosaic=1 + +letter_box=1 + +ema_alpha=0.9998 + +#optimized_memory=1 + +#23:104x104 54:52x52 85:26x26 104:13x13 for 416 + + + +[convolutional] +batch_normalize=1 +filters=32 +size=3 +stride=1 +pad=1 +activation=mish + +# Downsample + +[convolutional] +batch_normalize=1 +filters=64 +size=3 +stride=2 +pad=1 +activation=mish + +#[convolutional] +#batch_normalize=1 +#filters=64 +#size=1 +#stride=1 +#pad=1 +#activation=mish + +#[route] +#layers = -2 + +#[convolutional] +#batch_normalize=1 +#filters=64 +#size=1 +#stride=1 +#pad=1 +#activation=mish + +[convolutional] +batch_normalize=1 +filters=32 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=64 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +#[convolutional] +#batch_normalize=1 +#filters=64 +#size=1 +#stride=1 +#pad=1 +#activation=mish + +#[route] +#layers = -1,-7 + +#[convolutional] +#batch_normalize=1 +#filters=64 +#size=1 +#stride=1 +#pad=1 +#activation=mish + +# Downsample + +[convolutional] +batch_normalize=1 +filters=128 +size=3 +stride=2 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=64 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=64 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -1,-10 + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +# Downsample + +[convolutional] +batch_normalize=1 +filters=256 +size=3 +stride=2 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -1,-28 + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +# Downsample + +[convolutional] +batch_normalize=1 +filters=512 +size=3 +stride=2 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -1,-28 + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +# Downsample + +[convolutional] +batch_normalize=1 +filters=1024 +size=3 +stride=2 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=512 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=512 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=512 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=512 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -1,-16 + +[convolutional] +batch_normalize=1 +filters=1024 +size=1 +stride=1 +pad=1 +activation=mish + +########################## + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=512 +activation=mish + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +### SPP ### +[maxpool] +stride=1 +size=5 + +[route] +layers=-2 + +[maxpool] +stride=1 +size=9 + +[route] +layers=-4 + +[maxpool] +stride=1 +size=13 + +[route] +layers=-1,-3,-5,-6 +### End SPP ### + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=512 +activation=mish + +[route] +layers = -1, -13 + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[upsample] +stride=2 + +[route] +layers = 79 + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -1, -3 + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=256 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=256 +activation=mish + +[route] +layers = -1, -6 + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[upsample] +stride=2 + +[route] +layers = 48 + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -1, -3 + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=128 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=128 +activation=mish + +[route] +layers = -1, -6 + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +########################## + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=256 +activation=mish + +[convolutional] +size=1 +stride=1 +pad=1 +filters=255 +activation=logistic + + +[yolo] +mask = 0,1,2 +anchors = 12, 16, 19, 36, 40, 28, 36, 75, 76, 55, 72, 146, 142, 110, 192, 243, 459, 401 +classes=80 +num=9 +jitter=.1 +scale_x_y = 2.0 +objectness_smooth=0 +ignore_thresh = .7 +truth_thresh = 1 +#random=1 +resize=1.5 +iou_thresh=0.2 +iou_normalizer=0.05 +cls_normalizer=0.5 +obj_normalizer=4.0 +iou_loss=ciou +nms_kind=diounms +beta_nms=0.6 +new_coords=1 +max_delta=5 + +[route] +layers = -4 + +[convolutional] +batch_normalize=1 +size=3 +stride=2 +pad=1 +filters=256 +activation=mish + +[route] +layers = -1, -20 + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=256 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=256 +activation=mish + +[route] +layers = -1,-6 + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=512 +activation=mish + +[convolutional] +size=1 +stride=1 +pad=1 +filters=255 +activation=logistic + + +[yolo] +mask = 3,4,5 +anchors = 12, 16, 19, 36, 40, 28, 36, 75, 76, 55, 72, 146, 142, 110, 192, 243, 459, 401 +classes=80 +num=9 +jitter=.1 +scale_x_y = 2.0 +objectness_smooth=1 +ignore_thresh = .7 +truth_thresh = 1 +#random=1 +resize=1.5 +iou_thresh=0.2 +iou_normalizer=0.05 +cls_normalizer=0.5 +obj_normalizer=1.0 +iou_loss=ciou +nms_kind=diounms +beta_nms=0.6 +new_coords=1 +max_delta=5 + +[route] +layers = -4 + +[convolutional] +batch_normalize=1 +size=3 +stride=2 +pad=1 +filters=512 +activation=mish + +[route] +layers = -1, -49 + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=512 +activation=mish + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=512 +activation=mish + +[route] +layers = -1,-6 + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=1024 +activation=mish + +[convolutional] +size=1 +stride=1 +pad=1 +filters=255 +activation=logistic + + +[yolo] +mask = 6,7,8 +anchors = 12, 16, 19, 36, 40, 28, 36, 75, 76, 55, 72, 146, 142, 110, 192, 243, 459, 401 +classes=80 +num=9 +jitter=.1 +scale_x_y = 2.0 +objectness_smooth=1 +ignore_thresh = .7 +truth_thresh = 1 +#random=1 +resize=1.5 +iou_thresh=0.2 +iou_normalizer=0.05 +cls_normalizer=0.5 +obj_normalizer=0.4 +iou_loss=ciou +nms_kind=diounms +beta_nms=0.6 +new_coords=1 +max_delta=2 diff --git a/darknet_ros/yolo_network_config/cfg/yolov2.cfg b/darknet_ros/yolo_network_config/cfg/yolov4-tiny.cfg similarity index 61% rename from darknet_ros/yolo_network_config/cfg/yolov2.cfg rename to darknet_ros/yolo_network_config/cfg/yolov4-tiny.cfg index 2a0cd98fb..503f9334d 100644 --- a/darknet_ros/yolo_network_config/cfg/yolov2.cfg +++ b/darknet_ros/yolo_network_config/cfg/yolov4-tiny.cfg @@ -1,10 +1,10 @@ [net] # Testing +#batch=1 +#subdivisions=1 +# Training batch=1 subdivisions=1 -# Training -# batch=64 -# subdivisions=8 width=416 height=416 channels=3 @@ -15,88 +15,80 @@ saturation = 1.5 exposure = 1.5 hue=.1 -learning_rate=0.001 +learning_rate=0.00261 burn_in=1000 -max_batches = 500200 + +max_batches = 2000200 policy=steps -steps=400000,450000 +steps=1600000,1800000 scales=.1,.1 + +#weights_reject_freq=1001 +#ema_alpha=0.9998 +#equidistant_point=1000 +#num_sigmas_reject_badlabels=3 +#badlabels_rejection_percentage=0.2 + + [convolutional] batch_normalize=1 filters=32 size=3 -stride=1 +stride=2 pad=1 activation=leaky -[maxpool] -size=2 -stride=2 - [convolutional] batch_normalize=1 filters=64 size=3 -stride=1 -pad=1 -activation=leaky - -[maxpool] -size=2 stride=2 - -[convolutional] -batch_normalize=1 -filters=128 -size=3 -stride=1 pad=1 activation=leaky [convolutional] batch_normalize=1 filters=64 -size=1 +size=3 stride=1 pad=1 activation=leaky +[route] +layers=-1 +groups=2 +group_id=1 + [convolutional] batch_normalize=1 -filters=128 +filters=32 size=3 stride=1 pad=1 activation=leaky -[maxpool] -size=2 -stride=2 - [convolutional] batch_normalize=1 -filters=256 +filters=32 size=3 stride=1 pad=1 activation=leaky +[route] +layers = -1,-2 + [convolutional] batch_normalize=1 -filters=128 +filters=64 size=1 stride=1 pad=1 activation=leaky -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky +[route] +layers = -6,-1 [maxpool] size=2 @@ -104,43 +96,46 @@ stride=2 [convolutional] batch_normalize=1 -filters=512 +filters=128 size=3 stride=1 pad=1 activation=leaky +[route] +layers=-1 +groups=2 +group_id=1 + [convolutional] batch_normalize=1 -filters=256 -size=1 +filters=64 +size=3 stride=1 pad=1 activation=leaky [convolutional] batch_normalize=1 -filters=512 +filters=64 size=3 stride=1 pad=1 activation=leaky +[route] +layers = -1,-2 + [convolutional] batch_normalize=1 -filters=256 +filters=128 size=1 stride=1 pad=1 activation=leaky -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky +[route] +layers = -6,-1 [maxpool] size=2 @@ -148,111 +143,152 @@ stride=2 [convolutional] batch_normalize=1 -filters=1024 +filters=256 size=3 stride=1 pad=1 activation=leaky +[route] +layers=-1 +groups=2 +group_id=1 + [convolutional] batch_normalize=1 -filters=512 -size=1 +filters=128 +size=3 stride=1 pad=1 activation=leaky [convolutional] batch_normalize=1 -filters=1024 +filters=128 size=3 stride=1 pad=1 activation=leaky +[route] +layers = -1,-2 + [convolutional] batch_normalize=1 -filters=512 +filters=256 size=1 stride=1 pad=1 activation=leaky +[route] +layers = -6,-1 + +[maxpool] +size=2 +stride=2 + [convolutional] batch_normalize=1 -filters=1024 +filters=512 size=3 stride=1 pad=1 activation=leaky - -####### +################################## [convolutional] batch_normalize=1 -size=3 +filters=256 +size=1 stride=1 pad=1 -filters=1024 activation=leaky [convolutional] batch_normalize=1 +filters=512 size=3 stride=1 pad=1 -filters=1024 activation=leaky +[convolutional] +size=1 +stride=1 +pad=1 +filters=255 +activation=linear + + + +[yolo] +mask = 3,4,5 +anchors = 10,14, 23,27, 37,58, 81,82, 135,169, 344,319 +classes=80 +num=6 +jitter=.3 +scale_x_y = 1.05 +cls_normalizer=1.0 +iou_normalizer=0.07 +iou_loss=ciou +ignore_thresh = .7 +truth_thresh = 1 +random=0 +resize=1.5 +nms_kind=greedynms +beta_nms=0.6 +#new_coords=1 +#scale_x_y = 2.0 + [route] -layers=-9 +layers = -4 [convolutional] batch_normalize=1 +filters=128 size=1 stride=1 pad=1 -filters=64 activation=leaky -[reorg] +[upsample] stride=2 [route] -layers=-1,-4 +layers = -1, 23 [convolutional] batch_normalize=1 +filters=256 size=3 stride=1 pad=1 -filters=1024 activation=leaky [convolutional] size=1 stride=1 pad=1 -filters=425 +filters=255 activation=linear - -[region] -anchors = 0.57273, 0.677385, 1.87446, 2.06253, 3.33843, 5.47434, 7.88282, 3.52778, 9.77052, 9.16828 -bias_match=1 +[yolo] +mask = 1,2,3 +anchors = 10,14, 23,27, 37,58, 81,82, 135,169, 344,319 classes=80 -coords=4 -num=5 -softmax=1 +num=6 jitter=.3 -rescore=1 - -object_scale=5 -noobject_scale=1 -class_scale=1 -coord_scale=1 - -absolute=1 -thresh = .6 -random=1 +scale_x_y = 1.05 +cls_normalizer=1.0 +iou_normalizer=0.07 +iou_loss=ciou +ignore_thresh = .7 +truth_thresh = 1 +random=0 +resize=1.5 +nms_kind=greedynms +beta_nms=0.6 +#new_coords=1 +#scale_x_y = 2.0 diff --git a/darknet_ros/yolo_network_config/cfg/yolov4.cfg b/darknet_ros/yolo_network_config/cfg/yolov4.cfg new file mode 100644 index 000000000..df1cbd523 --- /dev/null +++ b/darknet_ros/yolo_network_config/cfg/yolov4.cfg @@ -0,0 +1,1160 @@ +[net] +# batch=64 +batch=1 +subdivisions=1 +# Training +#width=512 +#height=512 +width=608 +height=608 +# width=416 +# height=416 +channels=3 +momentum=0.949 +decay=0.0005 +angle=0 +saturation = 1.5 +exposure = 1.5 +hue=.1 + +learning_rate=0.0013 +burn_in=1000 +max_batches = 500500 +policy=steps +steps=400000,450000 +scales=.1,.1 + +#cutmix=1 +mosaic=1 + +#:104x104 54:52x52 85:26x26 104:13x13 for 416 + +[convolutional] +batch_normalize=1 +filters=32 +size=3 +stride=1 +pad=1 +activation=mish + +# Downsample + +[convolutional] +batch_normalize=1 +filters=64 +size=3 +stride=2 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=32 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=64 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -1,-7 + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=mish + +# Downsample + +[convolutional] +batch_normalize=1 +filters=128 +size=3 +stride=2 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=64 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=64 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -1,-10 + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +# Downsample + +[convolutional] +batch_normalize=1 +filters=256 +size=3 +stride=2 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=128 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -1,-28 + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +# Downsample + +[convolutional] +batch_normalize=1 +filters=512 +size=3 +stride=2 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=256 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -1,-28 + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +# Downsample + +[convolutional] +batch_normalize=1 +filters=1024 +size=3 +stride=2 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=512 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=512 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=512 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=512 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -1,-16 + +[convolutional] +batch_normalize=1 +filters=1024 +size=1 +stride=1 +pad=1 +activation=mish + +########################## + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=leaky + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=1024 +activation=leaky + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=leaky + +### SPP ### +[maxpool] +stride=1 +size=5 + +[route] +layers=-2 + +[maxpool] +stride=1 +size=9 + +[route] +layers=-4 + +[maxpool] +stride=1 +size=13 + +[route] +layers=-1,-3,-5,-6 +### End SPP ### + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=leaky + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=1024 +activation=leaky + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=leaky + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=leaky + +[upsample] +stride=2 + +[route] +layers = 85 + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=leaky + +[route] +layers = -1, -3 + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=leaky + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=512 +activation=leaky + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=leaky + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=512 +activation=leaky + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=leaky + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=leaky + +[upsample] +stride=2 + +[route] +layers = 54 + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=leaky + +[route] +layers = -1, -3 + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=leaky + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=256 +activation=leaky + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=leaky + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=256 +activation=leaky + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=leaky + +########################## + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=256 +activation=leaky + +[convolutional] +size=1 +stride=1 +pad=1 +filters=255 +activation=linear + + +[yolo] +mask = 0,1,2 +anchors = 12, 16, 19, 36, 40, 28, 36, 75, 76, 55, 72, 146, 142, 110, 192, 243, 459, 401 +classes=80 +num=9 +jitter=.3 +ignore_thresh = .7 +truth_thresh = 1 +scale_x_y = 1.2 +iou_thresh=0.213 +cls_normalizer=1.0 +iou_normalizer=0.07 +iou_loss=ciou +nms_kind=greedynms +beta_nms=0.6 +max_delta=5 + + +[route] +layers = -4 + +[convolutional] +batch_normalize=1 +size=3 +stride=2 +pad=1 +filters=256 +activation=leaky + +[route] +layers = -1, -16 + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=leaky + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=512 +activation=leaky + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=leaky + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=512 +activation=leaky + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=leaky + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=512 +activation=leaky + +[convolutional] +size=1 +stride=1 +pad=1 +filters=255 +activation=linear + + +[yolo] +mask = 3,4,5 +anchors = 12, 16, 19, 36, 40, 28, 36, 75, 76, 55, 72, 146, 142, 110, 192, 243, 459, 401 +classes=80 +num=9 +jitter=.3 +ignore_thresh = .7 +truth_thresh = 1 +scale_x_y = 1.1 +iou_thresh=0.213 +cls_normalizer=1.0 +iou_normalizer=0.07 +iou_loss=ciou +nms_kind=greedynms +beta_nms=0.6 +max_delta=5 + + +[route] +layers = -4 + +[convolutional] +batch_normalize=1 +size=3 +stride=2 +pad=1 +filters=512 +activation=leaky + +[route] +layers = -1, -37 + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=leaky + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=1024 +activation=leaky + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=leaky + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=1024 +activation=leaky + +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=leaky + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=1024 +activation=leaky + +[convolutional] +size=1 +stride=1 +pad=1 +filters=255 +activation=linear + + +[yolo] +mask = 6,7,8 +anchors = 12, 16, 19, 36, 40, 28, 36, 75, 76, 55, 72, 146, 142, 110, 192, 243, 459, 401 +classes=80 +num=9 +jitter=.3 +ignore_thresh = .7 +truth_thresh = 1 +random=1 +scale_x_y = 1.05 +iou_thresh=0.213 +cls_normalizer=1.0 +iou_normalizer=0.07 +iou_loss=ciou +nms_kind=greedynms +beta_nms=0.6 +max_delta=5 diff --git a/darknet_ros/yolo_network_config/cfg/yolov3-voc.cfg b/darknet_ros/yolo_network_config/cfg/yolov7-tiny.cfg similarity index 60% rename from darknet_ros/yolo_network_config/cfg/yolov3-voc.cfg rename to darknet_ros/yolo_network_config/cfg/yolov7-tiny.cfg index 3f3e8dfb3..4628b43fc 100644 --- a/darknet_ros/yolo_network_config/cfg/yolov3-voc.cfg +++ b/darknet_ros/yolo_network_config/cfg/yolov7-tiny.cfg @@ -1,10 +1,10 @@ [net] # Testing - batch=1 - subdivisions=1 +#batch=1 +#subdivisions=1 # Training -# batch=64 -# subdivisions=16 +batch=1 +subdivisions=1 width=416 height=416 channels=3 @@ -15,25 +15,24 @@ saturation = 1.5 exposure = 1.5 hue=.1 -learning_rate=0.001 +learning_rate=0.00261 burn_in=1000 -max_batches = 50200 + +max_batches = 2000200 policy=steps -steps=40000,45000 +steps=1600000,1800000 scales=.1,.1 - - +# 0 [convolutional] batch_normalize=1 filters=32 size=3 -stride=1 +stride=2 pad=1 activation=leaky -# Downsample - +# 1 [convolutional] batch_normalize=1 filters=64 @@ -50,48 +49,37 @@ stride=1 pad=1 activation=leaky +[route] +layers=-2 + [convolutional] batch_normalize=1 -filters=64 -size=3 +filters=32 +size=1 stride=1 pad=1 activation=leaky -[shortcut] -from=-3 -activation=linear - -# Downsample - [convolutional] batch_normalize=1 -filters=128 +filters=32 size=3 -stride=2 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=64 -size=1 stride=1 pad=1 activation=leaky [convolutional] batch_normalize=1 -filters=128 +filters=32 size=3 stride=1 pad=1 activation=leaky -[shortcut] -from=-3 -activation=linear +[route] +layers = -5,-3,-2,-1 +# 8 [convolutional] batch_normalize=1 filters=64 @@ -100,51 +88,24 @@ stride=1 pad=1 activation=leaky -[convolutional] -batch_normalize=1 -filters=128 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -# Downsample - -[convolutional] -batch_normalize=1 -filters=256 -size=3 +[maxpool] +size=2 stride=2 -pad=1 -activation=leaky [convolutional] batch_normalize=1 -filters=128 +filters=64 size=1 stride=1 pad=1 activation=leaky -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear +[route] +layers=-2 [convolutional] batch_normalize=1 -filters=128 +filters=64 size=1 stride=1 pad=1 @@ -152,36 +113,24 @@ activation=leaky [convolutional] batch_normalize=1 -filters=256 +filters=64 size=3 stride=1 pad=1 activation=leaky -[shortcut] -from=-3 -activation=linear - [convolutional] batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 +filters=64 size=3 stride=1 pad=1 activation=leaky -[shortcut] -from=-3 -activation=linear +[route] +layers = -5,-3,-2,-1 +# 16 [convolutional] batch_normalize=1 filters=128 @@ -190,18 +139,20 @@ stride=1 pad=1 activation=leaky +[maxpool] +size=2 +stride=2 + [convolutional] batch_normalize=1 -filters=256 -size=3 +filters=128 +size=1 stride=1 pad=1 activation=leaky -[shortcut] -from=-3 -activation=linear - +[route] +layers=-2 [convolutional] batch_normalize=1 @@ -213,59 +164,50 @@ activation=leaky [convolutional] batch_normalize=1 -filters=256 +filters=128 size=3 stride=1 pad=1 activation=leaky -[shortcut] -from=-3 -activation=linear - [convolutional] batch_normalize=1 filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 size=3 stride=1 pad=1 activation=leaky -[shortcut] -from=-3 -activation=linear +[route] +layers = -5,-3,-2,-1 +# 24 [convolutional] batch_normalize=1 -filters=128 +filters=256 size=1 stride=1 pad=1 activation=leaky +[maxpool] +size=2 +stride=2 + [convolutional] batch_normalize=1 filters=256 -size=3 +size=1 stride=1 pad=1 activation=leaky -[shortcut] -from=-3 -activation=linear +[route] +layers=-2 [convolutional] batch_normalize=1 -filters=128 +filters=256 size=1 stride=1 pad=1 @@ -279,41 +221,30 @@ stride=1 pad=1 activation=leaky -[shortcut] -from=-3 -activation=linear - -# Downsample - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=2 -pad=1 -activation=leaky - [convolutional] batch_normalize=1 filters=256 -size=1 +size=3 stride=1 pad=1 activation=leaky +[route] +layers = -5,-3,-2,-1 + +# 32 [convolutional] batch_normalize=1 filters=512 -size=3 +size=1 stride=1 pad=1 activation=leaky -[shortcut] -from=-3 -activation=linear +################################## +### SPPCSP ### [convolutional] batch_normalize=1 filters=256 @@ -322,18 +253,8 @@ stride=1 pad=1 activation=leaky -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - +[route] +layers = -2 [convolutional] batch_normalize=1 @@ -343,38 +264,28 @@ stride=1 pad=1 activation=leaky -[convolutional] -batch_normalize=1 -filters=512 -size=3 +### SPP ### +[maxpool] stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear +size=5 +[route] +layers=-2 -[convolutional] -batch_normalize=1 -filters=256 -size=1 +[maxpool] stride=1 -pad=1 -activation=leaky +size=9 -[convolutional] -batch_normalize=1 -filters=512 -size=3 +[route] +layers=-4 + +[maxpool] stride=1 -pad=1 -activation=leaky +size=13 -[shortcut] -from=-3 -activation=linear +[route] +layers=-1,-3,-5,-6 +### End SPP ### [convolutional] batch_normalize=1 @@ -384,19 +295,10 @@ stride=1 pad=1 activation=leaky -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - +[route] +layers = -10,-1 +# 44 [convolutional] batch_normalize=1 filters=256 @@ -404,43 +306,47 @@ size=1 stride=1 pad=1 activation=leaky +### End SPPCSP ### [convolutional] batch_normalize=1 -filters=512 -size=3 +filters=128 +size=1 stride=1 pad=1 activation=leaky -[shortcut] -from=-3 -activation=linear +[upsample] +stride=2 +[route] +layers = 24 [convolutional] batch_normalize=1 -filters=256 +filters=128 size=1 stride=1 pad=1 activation=leaky +[route] +layers = -1,-3 + [convolutional] batch_normalize=1 -filters=512 -size=3 +filters=64 +size=1 stride=1 pad=1 activation=leaky -[shortcut] -from=-3 -activation=linear +[route] +layers=-2 [convolutional] batch_normalize=1 -filters=256 +filters=64 size=1 stride=1 pad=1 @@ -448,29 +354,27 @@ activation=leaky [convolutional] batch_normalize=1 -filters=512 +filters=64 size=3 stride=1 pad=1 activation=leaky -[shortcut] -from=-3 -activation=linear - -# Downsample - [convolutional] batch_normalize=1 -filters=1024 +filters=64 size=3 -stride=2 +stride=1 pad=1 activation=leaky +[route] +layers = -5,-3,-2,-1 + +# 56 [convolutional] batch_normalize=1 -filters=512 +filters=128 size=1 stride=1 pad=1 @@ -478,39 +382,43 @@ activation=leaky [convolutional] batch_normalize=1 -filters=1024 -size=3 +filters=64 +size=1 stride=1 pad=1 activation=leaky -[shortcut] -from=-3 -activation=linear +[upsample] +stride=2 + +[route] +layers = 16 [convolutional] batch_normalize=1 -filters=512 +filters=64 size=1 stride=1 pad=1 activation=leaky +[route] +layers = -1,-3 + [convolutional] batch_normalize=1 -filters=1024 -size=3 +filters=32 +size=1 stride=1 pad=1 activation=leaky -[shortcut] -from=-3 -activation=linear +[route] +layers=-2 [convolutional] batch_normalize=1 -filters=512 +filters=32 size=1 stride=1 pad=1 @@ -518,73 +426,59 @@ activation=leaky [convolutional] batch_normalize=1 -filters=1024 +filters=32 size=3 stride=1 pad=1 activation=leaky -[shortcut] -from=-3 -activation=linear - [convolutional] batch_normalize=1 -filters=512 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=1024 +filters=32 size=3 stride=1 pad=1 activation=leaky -[shortcut] -from=-3 -activation=linear - -###################### +[route] +layers = -5,-3,-2,-1 +# 68 [convolutional] batch_normalize=1 -filters=512 +filters=64 size=1 stride=1 pad=1 activation=leaky +########################## + [convolutional] batch_normalize=1 size=3 -stride=1 +stride=2 pad=1 -filters=1024 +filters=128 activation=leaky +[route] +layers = -1,56 + [convolutional] batch_normalize=1 -filters=512 +filters=64 size=1 stride=1 pad=1 activation=leaky -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=1024 -activation=leaky +[route] +layers=-2 [convolutional] batch_normalize=1 -filters=512 +filters=64 size=1 stride=1 pad=1 @@ -592,51 +486,27 @@ activation=leaky [convolutional] batch_normalize=1 +filters=64 size=3 stride=1 pad=1 -filters=1024 activation=leaky -[convolutional] -size=1 -stride=1 -pad=1 -filters=75 -activation=linear - -[yolo] -mask = 6,7,8 -anchors = 10,13, 16,30, 33,23, 30,61, 62,45, 59,119, 116,90, 156,198, 373,326 -classes=20 -num=9 -jitter=.3 -ignore_thresh = .5 -truth_thresh = 1 -random=1 - -[route] -layers = -4 - [convolutional] batch_normalize=1 -filters=256 -size=1 +filters=64 +size=3 stride=1 pad=1 activation=leaky -[upsample] -stride=2 - [route] -layers = -1, 61 - - +layers = -5,-3,-2,-1 +# 77 [convolutional] batch_normalize=1 -filters=256 +filters=128 size=1 stride=1 pad=1 @@ -645,30 +515,28 @@ activation=leaky [convolutional] batch_normalize=1 size=3 -stride=1 +stride=2 pad=1 -filters=512 +filters=256 activation=leaky +[route] +layers = -1,44 + [convolutional] batch_normalize=1 -filters=256 +filters=128 size=1 stride=1 pad=1 activation=leaky -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=512 -activation=leaky +[route] +layers=-2 [convolutional] batch_normalize=1 -filters=256 +filters=128 size=1 stride=1 pad=1 @@ -676,71 +544,85 @@ activation=leaky [convolutional] batch_normalize=1 +filters=128 size=3 stride=1 pad=1 -filters=512 activation=leaky [convolutional] -size=1 +batch_normalize=1 +filters=128 +size=3 stride=1 pad=1 -filters=75 -activation=linear - -[yolo] -mask = 3,4,5 -anchors = 10,13, 16,30, 33,23, 30,61, 62,45, 59,119, 116,90, 156,198, 373,326 -classes=20 -num=9 -jitter=.3 -ignore_thresh = .5 -truth_thresh = 1 -random=1 +activation=leaky [route] -layers = -4 +layers = -5,-3,-2,-1 +# 86 [convolutional] batch_normalize=1 -filters=128 +filters=256 size=1 stride=1 pad=1 activation=leaky -[upsample] -stride=2 +############################# -[route] -layers = -1, 36 +# ============ End of Neck ============ # +# ============ Head ============ # -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky +# P3 +[route] +layers = 68 [convolutional] batch_normalize=1 size=3 stride=1 pad=1 -filters=256 +filters=128 activation=leaky [convolutional] -batch_normalize=1 -filters=128 size=1 stride=1 pad=1 -activation=leaky +filters=255 +#activation=linear +activation=logistic + +[yolo] +mask = 0,1,2 +anchors = 10,13, 16,30, 33,23, 30,61, 62,45, 59,119, 116,90, 156,198, 373,326 +classes=80 +num=9 +jitter=.1 +scale_x_y = 2.0 +objectness_smooth=1 +ignore_thresh = .7 +truth_thresh = 1 +#random=1 +resize=1.5 +iou_thresh=0.2 +iou_normalizer=0.05 +cls_normalizer=0.5 +obj_normalizer=1.0 +iou_loss=ciou +nms_kind=diounms +beta_nms=0.6 +new_coords=1 +max_delta=2 + + +# P4 +[route] +layers = 77 [convolutional] batch_normalize=1 @@ -751,35 +633,74 @@ filters=256 activation=leaky [convolutional] -batch_normalize=1 -filters=128 size=1 stride=1 pad=1 -activation=leaky +filters=255 +#activation=linear +activation=logistic + +[yolo] +mask = 3,4,5 +anchors = 10,13, 16,30, 33,23, 30,61, 62,45, 59,119, 116,90, 156,198, 373,326 +classes=80 +num=9 +jitter=.1 +scale_x_y = 2.0 +objectness_smooth=1 +ignore_thresh = .7 +truth_thresh = 1 +#random=1 +resize=1.5 +iou_thresh=0.2 +iou_normalizer=0.05 +cls_normalizer=0.5 +obj_normalizer=1.0 +iou_loss=ciou +nms_kind=diounms +beta_nms=0.6 +new_coords=1 +max_delta=2 + + +# P5 +[route] +layers = 86 [convolutional] batch_normalize=1 size=3 stride=1 pad=1 -filters=256 +filters=512 activation=leaky [convolutional] size=1 stride=1 pad=1 -filters=75 -activation=linear +filters=255 +#activation=linear +activation=logistic [yolo] -mask = 0,1,2 -anchors = 10,13, 16,30, 33,23, 30,61, 62,45, 59,119, 116,90, 156,198, 373,326 -classes=20 +mask = 6,7,8 +anchors = 10,13, 16,30, 33,23, 30,61, 62,45, 59,119, 116,90, 156,198, 373,326 +classes=80 num=9 -jitter=.3 -ignore_thresh = .5 +jitter=.1 +scale_x_y = 2.0 +objectness_smooth=1 +ignore_thresh = .7 truth_thresh = 1 -random=1 - +#random=1 +resize=1.5 +iou_thresh=0.2 +iou_normalizer=0.05 +cls_normalizer=0.5 +obj_normalizer=1.0 +iou_loss=ciou +nms_kind=diounms +beta_nms=0.6 +new_coords=1 +max_delta=2 diff --git a/darknet_ros_msgs/CHANGELOG.rst b/darknet_ros_msgs/CHANGELOG.rst index cb25f7991..e6eedfdac 100644 --- a/darknet_ros_msgs/CHANGELOG.rst +++ b/darknet_ros_msgs/CHANGELOG.rst @@ -2,6 +2,16 @@ Changelog for package darknet_ros_msgs ^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^^ +1.1.5 (2021-04-08) +------------------ +* Merge pull request `#189 `_ from martinspedro/master + /darknet_ros/found_object uses custom msg with Header for improving synchronization +* std_msgs::Int8 with Header for Object Count +* Merge pull request `#183 `_ from kunaltyagi/id_num + Add numerical ID and launch param for image +* Adding numerical ID and launch param for image +* Contributors: Kunal Tyagi, Marko Bjelonic, Pedro Martins + 1.1.4 (2019-03-03) ------------------ diff --git a/darknet_ros_msgs/package.xml b/darknet_ros_msgs/package.xml index 1a16d3d9b..e70bb283a 100644 --- a/darknet_ros_msgs/package.xml +++ b/darknet_ros_msgs/package.xml @@ -2,7 +2,7 @@ darknet_ros_msgs - 1.1.4 + 1.1.5 Darknet is an open source neural network framework that runs on CPU and GPU. You only look once (YOLO) is a state-of-the-art, real-time object detection system. Marko Bjelonic BSD diff --git a/rm_darknet_CMakeLists.sh b/rm_darknet_CMakeLists.sh new file mode 100755 index 000000000..13d9bae80 --- /dev/null +++ b/rm_darknet_CMakeLists.sh @@ -0,0 +1,4 @@ +#!/bin/sh +SCRIPT_DIR=$(cd $(dirname $0); pwd) +rm $SCRIPT_DIR/darknet/CMakeLists.txt +rm $SCRIPT_DIR/darknet/src/csharp/CMakeLists.txt \ No newline at end of file