diff --git a/.gitmodules b/.gitmodules
index 7e7bece16..9bde5e7f3 100644
--- a/.gitmodules
+++ b/.gitmodules
@@ -1,3 +1,3 @@
[submodule "darknet"]
path = darknet
- url = https://github.com/leggedrobotics/darknet
+ url = https://github.com/AlexeyAB/darknet.git
diff --git a/darknet b/darknet
index d22bbf38b..86ced7151 160000
--- a/darknet
+++ b/darknet
@@ -1 +1 @@
-Subproject commit d22bbf38bd012f13d2b50c8d98149cd4a9889b7a
+Subproject commit 86ced7151a71c05fab57bc14f77d6a4bb97b9ee6
diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt
index 9a7be7da5..2029ae11f 100644
--- a/darknet_ros/CMakeLists.txt
+++ b/darknet_ros/CMakeLists.txt
@@ -6,6 +6,9 @@ set(CMAKE_CXX_STANDARD 11)
set(CMAKE_C_FLAGS "-Wall -Wno-unused-result -Wno-unknown-pragmas -Wno-unused-variable -Wfatal-errors -fPIC ${CMAKE_C_FLAGS}")
set(CMAKE_EXPORT_COMPILE_COMMANDS ON)
+enable_language(C)
+enable_language(CXX)
+
# Define path of darknet folder here.
find_path(DARKNET_PATH
NAMES "README.md"
@@ -13,28 +16,79 @@ find_path(DARKNET_PATH
message(STATUS "Darknet path dir = ${DARKNET_PATH}")
add_definitions(-DDARKNET_FILE_PATH="${DARKNET_PATH}")
+#Darknet extra modules
+set(CMAKE_MODULE_PATH "${DARKNET_PATH}/cmake/Modules/" ${CMAKE_MODULE_PATH})
+
# Find CUDA
find_package(CUDA QUIET)
+
if (CUDA_FOUND)
- find_package(CUDA REQUIRED)
- 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
- )
- add_definitions(-DGPU)
+ # Get CUDA Compute capability with modified script from internet
+ set(CUDAFILE ${CMAKE_CURRENT_SOURCE_DIR}/scripts/check_cuda.cu)
+ set(OUTPUTFILE ${CMAKE_CURRENT_SOURCE_DIR}/scripts/cuda_check)
+ # Compile cuda arch check script
+ execute_process(COMMAND nvcc -lcuda ${CUDAFILE} -o ${OUTPUTFILE})
+ execute_process(COMMAND ${OUTPUTFILE}
+ RESULT_VARIABLE CUDA_RETURN_CODE
+ OUTPUT_VARIABLE GENCODE)
+ #Check correct architectures and capabilities
+ if(${CUDA_RETURN_CODE} EQUAL 0)
+ set(CUDA_SUCCESS "TRUE")
+ else()
+ message(Warning"${GENCODE}. Forcing darknet_ros without CUDA")
+ set(CUDA_SUCCESS "FALSE")
+ endif()
+ #remove cuda_check binary
+ execute_process(COMMAND rm -f ${OUTPUTFILE})
+ #Config CUDA
+ if (${CUDA_SUCCESS})
+ set(
+ CUDA_NVCC_FLAGS
+ ${CUDA_NVCC_FLAGS};
+ -O3
+ #-gencode arch=compute_30,code=sm_30 deprecated for CUDA9+
+ #-gencode arch=compute_35,code=sm_35 deprecated for CUDA9+
+ # -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} # Force to compile to installed GPUs Architectures
+ )
+ message(STATUS "CUDA Architecture: ${GENCODE}")
+ message(STATUS "CUDA Version: ${CUDA_VERSION_STRING}")
+ message(STATUS "CUDA Version: ${CUDA_VERSION_STRINGS}")
+ message(STATUS "CUDA Libararies: ${CUDA_LIBRARIES}")
+ add_definitions(-DGPU)
+ else()
+ list(APPEND LIBRARIES "m")
+ endif()
else()
list(APPEND LIBRARIES "m")
endif()
+# Find CUDNN
+if(CUDA_SUCCESS)
+ find_package(CUDNN)
+ if (CUDNN_FOUND)
+ message(STATUS "CUDNN Version: ${CUDNN_VERSION_STRINGS}")
+ message(STATUS "CUDNN Libararies: ${CUDNN_LIBRARIES}")
+ set(ADDITIONAL_CXX_FLAGS "${ADDITIONAL_CXX_FLAGS} -DCUDNN")
+ # ENABLE CUDNN_HALF
+ if ( "-gencode arch=compute_70,code=sm_70" IN_LIST CUDA_NVCC_FLAGS OR
+ "-gencode arch=compute_72,code=sm_72" IN_LIST CUDA_NVCC_FLAGS OR
+ "-gencode arch=compute_75,code=sm_75" IN_LIST CUDA_NVCC_FLAGS OR
+ "-gencode arch=compute_80,code=sm_80" IN_LIST CUDA_NVCC_FLAGS OR
+ "-gencode arch=compute_86,code=sm_86" IN_LIST CUDA_NVCC_FLAGS)
+ set(ENABLE_CUDNN_HALF "TRUE" CACHE BOOL "Enable CUDNN Half precision" FORCE)
+ message(STATUS "Your setup supports half precision (CUDA_ARCHITECTURES >= 70)")
+ else()
+ 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()
+ endif()
+endif()
+
+
# Find X11
message ( STATUS "Searching for X11..." )
find_package ( X11 REQUIRED )
@@ -65,6 +119,15 @@ find_package(catkin REQUIRED
add_definitions(-DOPENCV)
add_definitions(-O4 -g)
+# Enable CUDNN in darknet
+if(CUDNN_FOUND)
+ add_definitions(-DCUDNN)
+ # Enable in darknet
+ if(ENABLE_CUDNN_HALF)
+ add_definitions(-DCUDNN)
+ endif()
+endif()
+
catkin_package(
INCLUDE_DIRS
include
@@ -86,6 +149,7 @@ catkin_package(
include_directories(
${DARKNET_PATH}/src
${DARKNET_PATH}/include
+ ${DARKNET_PATH}/3rdparty/stb/include
include
${Boost_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS}
@@ -93,53 +157,58 @@ include_directories(
set(PROJECT_LIB_FILES
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}/src/iseg_layer.c ${DARKNET_PATH}/src/image_opencv.cpp
-
- ${DARKNET_PATH}/examples/art.c ${DARKNET_PATH}/examples/lsd.c
- ${DARKNET_PATH}/examples/nightmare.c ${DARKNET_PATH}/examples/instance-segmenter.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/data.c
+ ${DARKNET_PATH}/src/deconvolutional_layer.c ${DARKNET_PATH}/src/detection_layer.c
+ ${DARKNET_PATH}/src/demo.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/representation_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
)
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
)
-if (CUDA_FOUND)
+if (CUDA_SUCCESS)
link_directories(
${CUDA_TOOLKIT_ROOT_DIR}/lib64
@@ -157,6 +226,14 @@ if (CUDA_FOUND)
curand
)
+ if(CUDNN_FOUND)
+ target_link_libraries(${PROJECT_NAME}_lib CuDNN::CuDNN)
+ target_compile_definitions(${PROJECT_NAME}_lib PUBLIC -DCUDNN)
+ if(ENABLE_CUDNN_HALF)
+ target_compile_definitions(${PROJECT_NAME}_lib PUBLIC -DCUDNN_HALF)
+ endif()
+ endif()
+
cuda_add_executable(${PROJECT_NAME}
src/yolo_object_detector_node.cpp
)
@@ -240,6 +317,15 @@ if (NOT EXISTS "${FILE}")
execute_process(COMMAND wget -q https://github.com/leggedrobotics/darknet_ros/releases/download/1.1.4/yolov3.weights -P ${PATH})
endif()
+#Download yolov4.weights
+
+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()
+
#############
## Testing ##
#############
@@ -280,3 +366,4 @@ if (cmake_clang_tools_FOUND)
CF_WERROR
)
endif (cmake_clang_tools_FOUND)
+
diff --git a/darknet_ros/config/ros.yaml b/darknet_ros/config/ros.yaml
index 04abce530..5e5927858 100644
--- a/darknet_ros/config/ros.yaml
+++ b/darknet_ros/config/ros.yaml
@@ -1,7 +1,7 @@
subscribers:
camera_reading:
- topic: /camera/rgb/image_raw
+ topic: /cv_camera/image_raw
queue_size: 1
actions:
diff --git a/darknet_ros/config/yolov4-tiny.yaml b/darknet_ros/config/yolov4-tiny.yaml
new file mode 100644
index 000000000..be54094b5
--- /dev/null
+++ b/darknet_ros/config/yolov4-tiny.yaml
@@ -0,0 +1,90 @@
+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
diff --git a/darknet_ros/config/yolov4.yaml b/darknet_ros/config/yolov4.yaml
new file mode 100644
index 000000000..e4ae6f384
--- /dev/null
+++ b/darknet_ros/config/yolov4.yaml
@@ -0,0 +1,90 @@
+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
diff --git a/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp b/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp
index 304b09395..ce3606fef 100644
--- a/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp
+++ b/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp
@@ -54,6 +54,8 @@ extern "C" {
#include "parser.h"
#include "region_layer.h"
#include "utils.h"
+#include "blas.h"
+#include "darknet.h"
}
// Image interface.
@@ -61,7 +63,7 @@ extern "C" {
extern "C" cv::Mat image_to_mat(image im);
extern "C" image mat_to_image(cv::Mat m);
-extern "C" int show_image(image p, const char* name, int ms);
+//extern "C" int show_image(image p, const char* name, int ms);
namespace darknet_ros {
diff --git a/darknet_ros/launch/darknet_ros.launch b/darknet_ros/launch/darknet_ros.launch
index 11ab56d09..75ed295c5 100644
--- a/darknet_ros/launch/darknet_ros.launch
+++ b/darknet_ros/launch/darknet_ros.launch
@@ -11,7 +11,7 @@
-
+
diff --git a/darknet_ros/scripts/check_cuda.cu b/darknet_ros/scripts/check_cuda.cu
new file mode 100644
index 000000000..c04fca29f
--- /dev/null
+++ b/darknet_ros/scripts/check_cuda.cu
@@ -0,0 +1,35 @@
+#include
+
+int main(int argc, char **argv){
+ cudaDeviceProp dP;
+ float min_cc = 3.0;
+ int deviceCount, rc;
+ rc = cudaGetDeviceCount(&deviceCount);
+
+ if(rc != cudaSuccess) {
+ cudaError_t error = cudaGetLastError();
+ printf("CUDA error: %s", cudaGetErrorString(error));
+ return rc; /* Failure */
+ }
+
+ for (int i=0; i < deviceCount; i++)
+ {
+ rc = cudaGetDeviceProperties(&dP, 0);
+ if(rc != cudaSuccess) {
+ cudaError_t error = cudaGetLastError();
+ printf("CUDA error: %s", cudaGetErrorString(error));
+ return rc; /* Failure */
+ }
+ if((dP.major+(dP.minor/10)) < min_cc) {
+ printf("Min Compute Capability of %2.1f required: %d.%d found\n Not Building CUDA Code", min_cc, dP.major, dP.minor);
+ return 1; /* Failure */
+ } else {
+ int v = dP.major*10 + dP.minor;
+ if (ilayers[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;
@@ -323,7 +323,7 @@ void* YoloObjectDetector::detectInThread() {
printf("Objects:\n\n");
}
image display = buff_[(buffIndex_ + 2) % 3];
- draw_detections(display, dets, nboxes, demoThresh_, demoNames_, demoAlphabet_, demoClasses_);
+ draw_detections_v3(display, dets, nboxes, demoThresh_, demoNames_, demoAlphabet_, demoClasses_, 0);
// extract the bounding boxes and send them to ROS
int i, j;
@@ -391,7 +391,8 @@ void* YoloObjectDetector::fetchInThread() {
}
void* YoloObjectDetector::displayInThread(void* ptr) {
- int c = show_image(buff_[(buffIndex_ + 1) % 3], "YOLO", 1);
+ show_image(buff_[(buffIndex_ + 1) % 3], "YOLO");
+ int c = cv::waitKey(waitKeyDelay_);
if (c != -1) c = c % 256;
if (c == 27) {
demoDone_ = 1;
diff --git a/darknet_ros/src/yolo_object_detector_node.cpp b/darknet_ros/src/yolo_object_detector_node.cpp
index d491665d8..358c2077e 100644
--- a/darknet_ros/src/yolo_object_detector_node.cpp
+++ b/darknet_ros/src/yolo_object_detector_node.cpp
@@ -9,11 +9,11 @@
#include
#include
-int main(int argc, char** argv) {
+int main(int argc, char** argv) {
+ cuda_debug_sync = find_arg(argc, argv, "-cuda_debug_sync");
ros::init(argc, argv, "darknet_ros");
ros::NodeHandle nodeHandle("~");
darknet_ros::YoloObjectDetector yoloObjectDetector(nodeHandle);
-
ros::spin();
return 0;
}
diff --git a/darknet_ros/yolo_network_config/cfg/yolov4-tiny.cfg b/darknet_ros/yolo_network_config/cfg/yolov4-tiny.cfg
new file mode 100644
index 000000000..d990b5134
--- /dev/null
+++ b/darknet_ros/yolo_network_config/cfg/yolov4-tiny.cfg
@@ -0,0 +1,294 @@
+[net]
+# Testing
+#batch=1
+#subdivisions=1
+# Training
+batch=64
+subdivisions=1
+width=416
+height=416
+channels=3
+momentum=0.9
+decay=0.0005
+angle=0
+saturation = 1.5
+exposure = 1.5
+hue=.1
+
+learning_rate=0.00261
+burn_in=1000
+
+max_batches = 2000200
+policy=steps
+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=2
+pad=1
+activation=leaky
+
+[convolutional]
+batch_normalize=1
+filters=64
+size=3
+stride=2
+pad=1
+activation=leaky
+
+[convolutional]
+batch_normalize=1
+filters=64
+size=3
+stride=1
+pad=1
+activation=leaky
+
+[route]
+layers=-1
+groups=2
+group_id=1
+
+[convolutional]
+batch_normalize=1
+filters=32
+size=3
+stride=1
+pad=1
+activation=leaky
+
+[convolutional]
+batch_normalize=1
+filters=32
+size=3
+stride=1
+pad=1
+activation=leaky
+
+[route]
+layers = -1,-2
+
+[convolutional]
+batch_normalize=1
+filters=64
+size=1
+stride=1
+pad=1
+activation=leaky
+
+[route]
+layers = -6,-1
+
+[maxpool]
+size=2
+stride=2
+
+[convolutional]
+batch_normalize=1
+filters=128
+size=3
+stride=1
+pad=1
+activation=leaky
+
+[route]
+layers=-1
+groups=2
+group_id=1
+
+[convolutional]
+batch_normalize=1
+filters=64
+size=3
+stride=1
+pad=1
+activation=leaky
+
+[convolutional]
+batch_normalize=1
+filters=64
+size=3
+stride=1
+pad=1
+activation=leaky
+
+[route]
+layers = -1,-2
+
+[convolutional]
+batch_normalize=1
+filters=128
+size=1
+stride=1
+pad=1
+activation=leaky
+
+[route]
+layers = -6,-1
+
+[maxpool]
+size=2
+stride=2
+
+[convolutional]
+batch_normalize=1
+filters=256
+size=3
+stride=1
+pad=1
+activation=leaky
+
+[route]
+layers=-1
+groups=2
+group_id=1
+
+[convolutional]
+batch_normalize=1
+filters=128
+size=3
+stride=1
+pad=1
+activation=leaky
+
+[convolutional]
+batch_normalize=1
+filters=128
+size=3
+stride=1
+pad=1
+activation=leaky
+
+[route]
+layers = -1,-2
+
+[convolutional]
+batch_normalize=1
+filters=256
+size=1
+stride=1
+pad=1
+activation=leaky
+
+[route]
+layers = -6,-1
+
+[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]
+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 = -4
+
+[convolutional]
+batch_normalize=1
+filters=128
+size=1
+stride=1
+pad=1
+activation=leaky
+
+[upsample]
+stride=2
+
+[route]
+layers = -1, 23
+
+[convolutional]
+batch_normalize=1
+filters=256
+size=3
+stride=1
+pad=1
+activation=leaky
+
+[convolutional]
+size=1
+stride=1
+pad=1
+filters=255
+activation=linear
+
+[yolo]
+mask = 1,2,3
+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
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..15b92f5a3
--- /dev/null
+++ b/darknet_ros/yolo_network_config/cfg/yolov4.cfg
@@ -0,0 +1,1158 @@
+[net]
+batch=1
+subdivisions=8
+# Training
+#width=512
+#height=512
+width=608
+height=608
+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/weights/how_to_download_weights.txt b/darknet_ros/yolo_network_config/weights/how_to_download_weights.txt
index 80e26a8bb..b625208bb 100644
--- a/darknet_ros/yolo_network_config/weights/how_to_download_weights.txt
+++ b/darknet_ros/yolo_network_config/weights/how_to_download_weights.txt
@@ -11,3 +11,8 @@ VOC data set (Yolo v2):
Yolo v3:
wget http://pjreddie.com/media/files/yolov3.weights
wget http://pjreddie.com/media/files/yolov3-voc.weights
+
+COCO data set (Yolo v4)
+
+ wget https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v3_optimal/yolov4.weights
+ wget https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v4_pre/yolov4-tiny.weights