From 207a5c832126d59a878c29f84fda9444b521a3b4 Mon Sep 17 00:00:00 2001 From: Tomas Gareau Date: Fri, 31 Jan 2020 16:28:28 +0100 Subject: [PATCH 01/64] 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. --- darknet_ros/CMakeLists.txt | 4 ++++ 1 file changed, 4 insertions(+) diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 9646428e0..f8b653add 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -203,6 +203,10 @@ install( FILES_MATCHING PATTERN "*.h" ) +install(DIRECTORY config launch yolo_network_config + DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} +) + # Download yolov2-tiny.weights set(PATH "${CMAKE_CURRENT_SOURCE_DIR}/yolo_network_config/weights") set(FILE "${PATH}/yolov2-tiny.weights") From b2530bfef7994acb0f74b220b32614d428593e65 Mon Sep 17 00:00:00 2001 From: Shih-Wei Guo Date: Thu, 13 Feb 2020 23:34:43 +0800 Subject: [PATCH 02/64] fix typo --- README.md | 12 ++++++------ 1 file changed, 6 insertions(+), 6 deletions(-) diff --git a/README.md b/README.md index 94aaafd33..68baa0cc1 100644 --- a/README.md +++ b/README.md @@ -128,7 +128,7 @@ You will see the image above popping up. ## 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 @@ -138,7 +138,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 @@ -168,7 +168,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) @@ -180,11 +180,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) @@ -192,4 +192,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/`. From f52eb7d105c7273dec1e36767434b2a77388b717 Mon Sep 17 00:00:00 2001 From: Marko Bjelonic Date: Sun, 12 Apr 2020 21:39:01 +0200 Subject: [PATCH 03/64] Added clang tooling. --- darknet_ros/CMakeLists.txt | 15 ++ .../darknet_ros/YoloObjectDetector.hpp | 101 ++++---- .../include/darknet_ros/image_interface.h | 4 +- darknet_ros/src/YoloObjectDetector.cpp | 229 +++++++----------- darknet_ros/src/image_interface.c | 40 ++- darknet_ros/src/yolo_object_detector_node.cpp | 2 +- darknet_ros/test/ObjectDetection.cpp | 98 ++++---- darknet_ros/test/test_main.cpp | 6 +- 8 files changed, 217 insertions(+), 278 deletions(-) diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index f8b653add..ba2b7f3de 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -4,6 +4,7 @@ project(darknet_ros) # Set c++11 cmake flags set(CMAKE_CXX_FLAGS "-std=c++11 ${CMAKE_CXX_FLAGS}") 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) # Define path of darknet folder here. find_path(DARKNET_PATH @@ -250,3 +251,17 @@ if(CATKIN_ENABLE_TESTING) ${catkin_LIBRARIES} ) endif() + +######################### +### CLANG TOOLING ### +######################### +find_package(cmake_clang_tools QUIET) +if (cmake_clang_tools_FOUND) + message(STATUS "Run clang tooling") + add_clang_tooling( + TARGETS ${PROJECT_NAME} + SOURCE_DIRS ${CMAKE_CURRENT_LIST_DIR}/src ${CMAKE_CURRENT_LIST_DIR}/include ${CMAKE_CURRENT_LIST_DIR}/test + CT_HEADER_DIRS ${CMAKE_CURRENT_LIST_DIR}/include + CF_WERROR + ) +endif (cmake_clang_tools_FOUND) diff --git a/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp b/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp index f1ab50a77..daef6ef67 100644 --- a/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp +++ b/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp @@ -9,75 +9,72 @@ #pragma once // c++ -#include -#include -#include -#include #include -#include #include +#include +#include +#include +#include +#include // ROS -#include -#include #include -#include -#include #include #include +#include +#include +#include +#include // OpenCv -#include +#include #include +#include #include -#include // darknet_ros_msgs -#include #include -#include +#include #include +#include // Darknet. #ifdef GPU +#include "cublas_v2.h" #include "cuda_runtime.h" #include "curand.h" -#include "cublas_v2.h" #endif extern "C" { -#include "network.h" +#include +#include "box.h" +#include "cost_layer.h" +#include "darknet_ros/image_interface.h" #include "detection_layer.h" +#include "network.h" +#include "parser.h" #include "region_layer.h" -#include "cost_layer.h" #include "utils.h" -#include "parser.h" -#include "box.h" -#include "darknet_ros/image_interface.h" -#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" void show_image_cv(image p, const char* name, IplImage* disp); namespace darknet_ros { //! Bounding box of the detected object. -typedef struct -{ +typedef struct { float x, y, w, h, prob; int num, Class; } RosBox_; -typedef struct -{ +typedef struct { IplImage* image; std_msgs::Header header; } IplImageWithHeader_; -class YoloObjectDetector -{ +class YoloObjectDetector { public: /*! * Constructor. @@ -129,9 +126,9 @@ class YoloObjectDetector */ bool publishDetectionImage(const cv::Mat& detectionImage); - //! Typedefs. - typedef actionlib::SimpleActionServer CheckForObjectsActionServer; - typedef std::shared_ptr CheckForObjectsActionServerPtr; + //! Using. + using CheckForObjectsActionServer = actionlib::SimpleActionServer; + using CheckForObjectsActionServerPtr = std::shared_ptr; //! ROS node handle. ros::NodeHandle nodeHandle_; @@ -167,17 +164,17 @@ class YoloObjectDetector std::thread yoloThread_; // Darknet. - char **demoNames_; - image **demoAlphabet_; + char** demoNames_; + image** demoAlphabet_; int demoClasses_; - network *net_; + network* net_; std_msgs::Header headerBuff_[3]; image buff_[3]; image buffLetter_[3]; int buffId_[3]; int buffIndex_ = 0; - IplImage * ipl_; + IplImage* ipl_; float fps_ = 0; float demoThresh_ = 0; float demoHier_ = .5; @@ -185,21 +182,21 @@ class YoloObjectDetector int demoDelay_ = 0; int demoFrame_ = 3; - float **predictions_; + float** predictions_; int demoIndex_ = 0; int demoDone_ = 0; - float *lastAvg2_; - float *lastAvg_; - float *avg_; + float* lastAvg2_; + float* lastAvg_; + float* avg_; int demoTotal_ = 0; double demoTime_; - RosBox_ *roiBoxes_; + RosBox_* roiBoxes_; bool viewImage_; bool enableConsoleOutput_; int waitKeyDelay_; int fullScreen_; - char *demoPrefix_; + char* demoPrefix_; std_msgs::Header imageHeader_; cv::Mat camImageCopy_; @@ -216,26 +213,24 @@ class YoloObjectDetector // double getWallTime(); - int sizeNetwork(network *net); + int sizeNetwork(network* net); - void rememberNetwork(network *net); + void rememberNetwork(network* net); - detection *avgPredictions(network *net, int *nboxes); + detection* avgPredictions(network* net, int* nboxes); - void *detectInThread(); + void* detectInThread(); - void *fetchInThread(); + void* fetchInThread(); - void *displayInThread(void *ptr); + void* displayInThread(void* ptr); - void *displayLoop(void *ptr); + void* displayLoop(void* ptr); - void *detectLoop(void *ptr); + void* detectLoop(void* ptr); - void setupNetwork(char *cfgfile, char *weightfile, char *datafile, float thresh, - char **names, int classes, - int delay, char *prefix, int avg_frames, float hier, int w, int h, - int frames, int fullscreen); + void setupNetwork(char* cfgfile, char* weightfile, char* datafile, float thresh, char** names, int classes, int delay, char* prefix, + int avg_frames, float hier, int w, int h, int frames, int fullscreen); void yolo(); @@ -245,7 +240,7 @@ class YoloObjectDetector bool isNodeRunning(void); - void *publishInThread(); + void* publishInThread(); }; } /* namespace darknet_ros*/ diff --git a/darknet_ros/include/darknet_ros/image_interface.h b/darknet_ros/include/darknet_ros/image_interface.h index 460549591..7fb3d49b1 100644 --- a/darknet_ros/include/darknet_ros/image_interface.h +++ b/darknet_ros/include/darknet_ros/image_interface.h @@ -12,7 +12,7 @@ #include "image.h" 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); +image** load_alphabet_with_file(char* datafile); +void generate_image(image p, IplImage* disp); #endif diff --git a/darknet_ros/src/YoloObjectDetector.cpp b/darknet_ros/src/YoloObjectDetector.cpp index 936a1e4a8..17cb41e7a 100644 --- a/darknet_ros/src/YoloObjectDetector.cpp +++ b/darknet_ros/src/YoloObjectDetector.cpp @@ -20,19 +20,13 @@ std::string darknetFilePath_ = DARKNET_FILE_PATH; namespace darknet_ros { -char *cfg; -char *weights; -char *data; -char **detectionNames; +char* cfg; +char* weights; +char* data; +char** detectionNames; YoloObjectDetector::YoloObjectDetector(ros::NodeHandle nh) - : nodeHandle_(nh), - imageTransport_(nodeHandle_), - numClasses_(0), - classLabels_(0), - rosBoxes_(0), - rosBoxCounter_(0) -{ + : nodeHandle_(nh), imageTransport_(nodeHandle_), numClasses_(0), classLabels_(0), rosBoxes_(0), rosBoxCounter_(0) { ROS_INFO("[YoloObjectDetector] Node started."); // Read parameters from config file. @@ -43,8 +37,7 @@ YoloObjectDetector::YoloObjectDetector(ros::NodeHandle nh) init(); } -YoloObjectDetector::~YoloObjectDetector() -{ +YoloObjectDetector::~YoloObjectDetector() { { boost::unique_lock lockNodeStatus(mutexNodeStatus_); isNodeRunning_ = false; @@ -52,8 +45,7 @@ YoloObjectDetector::~YoloObjectDetector() yoloThread_.join(); } -bool YoloObjectDetector::readParameters() -{ +bool YoloObjectDetector::readParameters() { // Load common parameters. nodeHandle_.param("image_view/enable_opencv", viewImage_, true); nodeHandle_.param("image_view/wait_key_delay", waitKeyDelay_, 3); @@ -69,8 +61,7 @@ bool YoloObjectDetector::readParameters() } // Set vector sizes. - nodeHandle_.param("yolo_model/detection_classes/names", classLabels_, - std::vector(0)); + nodeHandle_.param("yolo_model/detection_classes/names", classLabels_, std::vector(0)); numClasses_ = classLabels_.size(); rosBoxes_ = std::vector >(numClasses_); rosBoxCounter_ = std::vector(numClasses_); @@ -78,8 +69,7 @@ bool YoloObjectDetector::readParameters() return true; } -void YoloObjectDetector::init() -{ +void YoloObjectDetector::init() { ROS_INFO("[YoloObjectDetector] init()."); // Initialize deep network of darknet. @@ -91,11 +81,10 @@ void YoloObjectDetector::init() // Threshold of object detection. float thresh; - nodeHandle_.param("yolo_model/threshold/value", thresh, (float) 0.3); + nodeHandle_.param("yolo_model/threshold/value", thresh, (float)0.3); // Path to weights file. - nodeHandle_.param("yolo_model/weight_file/name", weightsModel, - std::string("yolov2-tiny.weights")); + nodeHandle_.param("yolo_model/weight_file/name", weightsModel, std::string("yolov2-tiny.weights")); nodeHandle_.param("weights_path", weightsPath, std::string("/default")); weightsPath += "/" + weightsModel; weights = new char[weightsPath.length() + 1]; @@ -115,15 +104,14 @@ void YoloObjectDetector::init() strcpy(data, dataPath.c_str()); // Get classes. - detectionNames = (char**) realloc((void*) detectionNames, (numClasses_ + 1) * sizeof(char*)); + detectionNames = (char**)realloc((void*)detectionNames, (numClasses_ + 1) * sizeof(char*)); for (int i = 0; i < numClasses_; i++) { detectionNames[i] = new char[classLabels_[i].length() + 1]; strcpy(detectionNames[i], classLabels_[i].c_str()); } // Load network. - setupNetwork(cfg, weights, data, thresh, detectionNames, numClasses_, - 0, 0, 1, 0.5, 0, 0, 0, 0); + setupNetwork(cfg, weights, data, thresh, detectionNames, numClasses_, 0, 0, 1, 0.5, 0, 0, 0, 0); yoloThread_ = std::thread(&YoloObjectDetector::yolo, this); // Initialize publisher and subscriber. @@ -139,48 +127,36 @@ void YoloObjectDetector::init() int detectionImageQueueSize; bool detectionImageLatch; - nodeHandle_.param("subscribers/camera_reading/topic", cameraTopicName, - std::string("/camera/image_raw")); + nodeHandle_.param("subscribers/camera_reading/topic", cameraTopicName, std::string("/camera/image_raw")); nodeHandle_.param("subscribers/camera_reading/queue_size", cameraQueueSize, 1); - nodeHandle_.param("publishers/object_detector/topic", objectDetectorTopicName, - std::string("found_object")); + nodeHandle_.param("publishers/object_detector/topic", objectDetectorTopicName, std::string("found_object")); nodeHandle_.param("publishers/object_detector/queue_size", objectDetectorQueueSize, 1); nodeHandle_.param("publishers/object_detector/latch", objectDetectorLatch, false); - nodeHandle_.param("publishers/bounding_boxes/topic", boundingBoxesTopicName, - std::string("bounding_boxes")); + nodeHandle_.param("publishers/bounding_boxes/topic", boundingBoxesTopicName, std::string("bounding_boxes")); nodeHandle_.param("publishers/bounding_boxes/queue_size", boundingBoxesQueueSize, 1); nodeHandle_.param("publishers/bounding_boxes/latch", boundingBoxesLatch, false); - nodeHandle_.param("publishers/detection_image/topic", detectionImageTopicName, - std::string("detection_image")); + nodeHandle_.param("publishers/detection_image/topic", detectionImageTopicName, std::string("detection_image")); nodeHandle_.param("publishers/detection_image/queue_size", detectionImageQueueSize, 1); nodeHandle_.param("publishers/detection_image/latch", detectionImageLatch, true); - imageSubscriber_ = imageTransport_.subscribe(cameraTopicName, cameraQueueSize, - &YoloObjectDetector::cameraCallback, this); - objectPublisher_ = nodeHandle_.advertise(objectDetectorTopicName, - objectDetectorQueueSize, - objectDetectorLatch); - boundingBoxesPublisher_ = nodeHandle_.advertise( - boundingBoxesTopicName, boundingBoxesQueueSize, boundingBoxesLatch); - detectionImagePublisher_ = nodeHandle_.advertise(detectionImageTopicName, - detectionImageQueueSize, - detectionImageLatch); + imageSubscriber_ = imageTransport_.subscribe(cameraTopicName, cameraQueueSize, &YoloObjectDetector::cameraCallback, this); + objectPublisher_ = + nodeHandle_.advertise(objectDetectorTopicName, objectDetectorQueueSize, objectDetectorLatch); + boundingBoxesPublisher_ = + nodeHandle_.advertise(boundingBoxesTopicName, boundingBoxesQueueSize, boundingBoxesLatch); + detectionImagePublisher_ = + nodeHandle_.advertise(detectionImageTopicName, detectionImageQueueSize, detectionImageLatch); // Action servers. std::string checkForObjectsActionName; - nodeHandle_.param("actions/camera_reading/topic", checkForObjectsActionName, - std::string("check_for_objects")); - checkForObjectsActionServer_.reset( - new CheckForObjectsActionServer(nodeHandle_, checkForObjectsActionName, false)); - checkForObjectsActionServer_->registerGoalCallback( - boost::bind(&YoloObjectDetector::checkForObjectsActionGoalCB, this)); - checkForObjectsActionServer_->registerPreemptCallback( - boost::bind(&YoloObjectDetector::checkForObjectsActionPreemptCB, this)); + nodeHandle_.param("actions/camera_reading/topic", checkForObjectsActionName, std::string("check_for_objects")); + checkForObjectsActionServer_.reset(new CheckForObjectsActionServer(nodeHandle_, checkForObjectsActionName, false)); + checkForObjectsActionServer_->registerGoalCallback(boost::bind(&YoloObjectDetector::checkForObjectsActionGoalCB, this)); + checkForObjectsActionServer_->registerPreemptCallback(boost::bind(&YoloObjectDetector::checkForObjectsActionPreemptCB, this)); checkForObjectsActionServer_->start(); } -void YoloObjectDetector::cameraCallback(const sensor_msgs::ImageConstPtr& msg) -{ +void YoloObjectDetector::cameraCallback(const sensor_msgs::ImageConstPtr& msg) { ROS_DEBUG("[YoloObjectDetector] USB image received."); cv_bridge::CvImagePtr cam_image; @@ -208,12 +184,10 @@ void YoloObjectDetector::cameraCallback(const sensor_msgs::ImageConstPtr& msg) return; } -void YoloObjectDetector::checkForObjectsActionGoalCB() -{ +void YoloObjectDetector::checkForObjectsActionGoalCB() { ROS_DEBUG("[YoloObjectDetector] Start check for objects action."); - boost::shared_ptr imageActionPtr = - checkForObjectsActionServer_->acceptNewGoal(); + boost::shared_ptr imageActionPtr = checkForObjectsActionServer_->acceptNewGoal(); sensor_msgs::Image imageAction = imageActionPtr->image; cv_bridge::CvImagePtr cam_image; @@ -244,22 +218,17 @@ void YoloObjectDetector::checkForObjectsActionGoalCB() return; } -void YoloObjectDetector::checkForObjectsActionPreemptCB() -{ +void YoloObjectDetector::checkForObjectsActionPreemptCB() { ROS_DEBUG("[YoloObjectDetector] Preempt check for objects action."); checkForObjectsActionServer_->setPreempted(); } -bool YoloObjectDetector::isCheckingForObjects() const -{ - return (ros::ok() && checkForObjectsActionServer_->isActive() - && !checkForObjectsActionServer_->isPreemptRequested()); +bool YoloObjectDetector::isCheckingForObjects() const { + return (ros::ok() && checkForObjectsActionServer_->isActive() && !checkForObjectsActionServer_->isPreemptRequested()); } -bool YoloObjectDetector::publishDetectionImage(const cv::Mat& detectionImage) -{ - if (detectionImagePublisher_.getNumSubscribers() < 1) - return false; +bool YoloObjectDetector::publishDetectionImage(const cv::Mat& detectionImage) { + if (detectionImagePublisher_.getNumSubscribers() < 1) return false; cv_bridge::CvImage cvImage; cvImage.header.stamp = ros::Time::now(); cvImage.header.frame_id = "detection_image"; @@ -279,62 +248,58 @@ bool YoloObjectDetector::publishDetectionImage(const cv::Mat& detectionImage) // return (double) time.tv_sec + (double) time.tv_usec * .000001; // } -int YoloObjectDetector::sizeNetwork(network *net) -{ +int YoloObjectDetector::sizeNetwork(network* net) { int i; int count = 0; - for(i = 0; i < net->n; ++i){ + for (i = 0; i < net->n; ++i) { layer l = net->layers[i]; - if(l.type == YOLO || l.type == REGION || l.type == DETECTION){ + if (l.type == YOLO || l.type == REGION || l.type == DETECTION) { count += l.outputs; } } return count; } -void YoloObjectDetector::rememberNetwork(network *net) -{ +void YoloObjectDetector::rememberNetwork(network* net) { int i; int count = 0; - for(i = 0; i < net->n; ++i){ + for (i = 0; i < net->n; ++i) { layer l = net->layers[i]; - if(l.type == YOLO || l.type == REGION || l.type == DETECTION){ + if (l.type == YOLO || l.type == REGION || l.type == DETECTION) { memcpy(predictions_[demoIndex_] + count, net->layers[i].output, sizeof(float) * l.outputs); count += l.outputs; } } } -detection *YoloObjectDetector::avgPredictions(network *net, int *nboxes) -{ +detection* YoloObjectDetector::avgPredictions(network* net, int* nboxes) { int i, j; int count = 0; fill_cpu(demoTotal_, 0, avg_, 1); - for(j = 0; j < demoFrame_; ++j){ - axpy_cpu(demoTotal_, 1./demoFrame_, predictions_[j], 1, avg_, 1); + for (j = 0; j < demoFrame_; ++j) { + axpy_cpu(demoTotal_, 1. / demoFrame_, predictions_[j], 1, avg_, 1); } - for(i = 0; i < net->n; ++i){ + for (i = 0; i < net->n; ++i) { layer l = net->layers[i]; - if(l.type == YOLO || l.type == REGION || l.type == DETECTION){ + if (l.type == YOLO || l.type == REGION || l.type == DETECTION) { memcpy(l.output, avg_ + count, sizeof(float) * l.outputs); 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); return dets; } -void *YoloObjectDetector::detectInThread() -{ +void* YoloObjectDetector::detectInThread() { running_ = 1; float nms = .4; layer l = net_->layers[net_->n - 1]; - float *X = buffLetter_[(buffIndex_ + 2) % 3].data; - float *prediction = network_predict(net_, X); + float* X = buffLetter_[(buffIndex_ + 2) % 3].data; + float* prediction = network_predict(net_, X); rememberNetwork(net_); - detection *dets = 0; + detection* dets = 0; int nboxes = 0; dets = avgPredictions(net_, &nboxes); @@ -343,10 +308,10 @@ void *YoloObjectDetector::detectInThread() if (enableConsoleOutput_) { printf("\033[2J"); printf("\033[1;1H"); - printf("\nFPS:%.1f\n",fps_); + printf("\nFPS:%.1f\n", fps_); printf("Objects:\n\n"); } - image display = buff_[(buffIndex_+2) % 3]; + image display = buff_[(buffIndex_ + 2) % 3]; draw_detections(display, dets, nboxes, demoThresh_, demoNames_, demoAlphabet_, demoClasses_); // extract the bounding boxes and send them to ROS @@ -358,14 +323,10 @@ void *YoloObjectDetector::detectInThread() float ymin = dets[i].bbox.y - dets[i].bbox.h / 2.; float ymax = dets[i].bbox.y + dets[i].bbox.h / 2.; - if (xmin < 0) - xmin = 0; - if (ymin < 0) - ymin = 0; - if (xmax > 1) - xmax = 1; - if (ymax > 1) - ymax = 1; + if (xmin < 0) xmin = 0; + if (ymin < 0) ymin = 0; + if (xmax > 1) xmax = 1; + if (ymax > 1) ymax = 1; // iterate through possible boxes and collect the bounding boxes for (j = 0; j < demoClasses_; ++j) { @@ -404,8 +365,7 @@ void *YoloObjectDetector::detectInThread() return 0; } -void *YoloObjectDetector::fetchInThread() -{ +void* YoloObjectDetector::fetchInThread() { { boost::shared_lock lock(mutexImageCallback_); IplImageWithHeader_ imageAndHeader = getIplImageWithHeader(); @@ -419,51 +379,45 @@ void *YoloObjectDetector::fetchInThread() return 0; } -void *YoloObjectDetector::displayInThread(void *ptr) -{ - show_image_cv(buff_[(buffIndex_ + 1)%3], "YOLO V3", ipl_); +void* YoloObjectDetector::displayInThread(void* ptr) { + show_image_cv(buff_[(buffIndex_ + 1) % 3], "YOLO V3", ipl_); 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) -{ +void* YoloObjectDetector::displayLoop(void* ptr) { while (1) { displayInThread(0); } } -void *YoloObjectDetector::detectLoop(void *ptr) -{ +void* YoloObjectDetector::detectLoop(void* ptr) { while (1) { detectInThread(); } } -void YoloObjectDetector::setupNetwork(char *cfgfile, char *weightfile, char *datafile, float thresh, - char **names, int classes, - int delay, char *prefix, int avg_frames, float hier, int w, int h, - int frames, int fullscreen) -{ +void YoloObjectDetector::setupNetwork(char* cfgfile, char* weightfile, char* datafile, float thresh, char** names, int classes, int delay, + char* prefix, int avg_frames, float hier, int w, int h, int frames, int fullscreen) { demoPrefix_ = prefix; demoDelay_ = delay; demoFrame_ = avg_frames; - image **alphabet = load_alphabet_with_file(datafile); + image** alphabet = load_alphabet_with_file(datafile); demoNames_ = names; demoAlphabet_ = alphabet; demoClasses_ = classes; @@ -475,8 +429,7 @@ void YoloObjectDetector::setupNetwork(char *cfgfile, char *weightfile, char *dat set_batch_network(net_, 1); } -void YoloObjectDetector::yolo() -{ +void YoloObjectDetector::yolo() { const auto wait_duration = std::chrono::milliseconds(2000); while (!getImageStatus()) { printf("Waiting for image.\n"); @@ -493,14 +446,14 @@ void YoloObjectDetector::yolo() int i; demoTotal_ = sizeNetwork(net_); - predictions_ = (float **) calloc(demoFrame_, sizeof(float*)); - for (i = 0; i < demoFrame_; ++i){ - predictions_[i] = (float *) calloc(demoTotal_, sizeof(float)); + predictions_ = (float**)calloc(demoFrame_, sizeof(float*)); + for (i = 0; i < demoFrame_; ++i) { + predictions_[i] = (float*)calloc(demoTotal_, sizeof(float)); } - avg_ = (float *) calloc(demoTotal_, sizeof(float)); + avg_ = (float*)calloc(demoTotal_, sizeof(float)); layer l = net_->layers[net_->n - 1]; - roiBoxes_ = (darknet_ros::RosBox_ *) calloc(l.w * l.h * l.n, sizeof(darknet_ros::RosBox_)); + roiBoxes_ = (darknet_ros::RosBox_*)calloc(l.w * l.h * l.n, sizeof(darknet_ros::RosBox_)); { boost::shared_lock lock(mutexImageCallback_); @@ -521,7 +474,7 @@ void YoloObjectDetector::yolo() int count = 0; if (!demoPrefix_ && viewImage_) { - cv::namedWindow("YOLO V3", cv::WINDOW_NORMAL); + cv::namedWindow("YOLO V3", cv::WINDOW_NORMAL); if (fullScreen_) { cv::setWindowProperty("YOLO V3", cv::WND_PROP_FULLSCREEN, cv::WINDOW_FULLSCREEN); } else { @@ -537,12 +490,12 @@ void YoloObjectDetector::yolo() fetch_thread = std::thread(&YoloObjectDetector::fetchInThread, this); detect_thread = std::thread(&YoloObjectDetector::detectInThread, this); if (!demoPrefix_) { - fps_ = 1./(what_time_is_it_now() - demoTime_); + fps_ = 1. / (what_time_is_it_now() - demoTime_); demoTime_ = what_time_is_it_now(); if (viewImage_) { displayInThread(0); } else { - generate_image(buff_[(buffIndex_ + 1)%3], ipl_); + generate_image(buff_[(buffIndex_ + 1) % 3], ipl_); } publishInThread(); } else { @@ -557,30 +510,25 @@ void YoloObjectDetector::yolo() demoDone_ = true; } } - } -IplImageWithHeader_ YoloObjectDetector::getIplImageWithHeader() -{ +IplImageWithHeader_ YoloObjectDetector::getIplImageWithHeader() { IplImage* ROS_img = new IplImage(camImageCopy_); IplImageWithHeader_ header = {.image = ROS_img, .header = imageHeader_}; return header; } -bool YoloObjectDetector::getImageStatus(void) -{ +bool YoloObjectDetector::getImageStatus(void) { boost::shared_lock lock(mutexImageStatus_); return imageStatus_; } -bool YoloObjectDetector::isNodeRunning(void) -{ +bool YoloObjectDetector::isNodeRunning(void) { boost::shared_lock lock(mutexNodeStatus_); return isNodeRunning_; } -void *YoloObjectDetector::publishInThread() -{ +void* YoloObjectDetector::publishInThread() { // Publish image. cv::Mat cvImage = cv::cvarrToMat(ipl_); if (!publishDetectionImage(cv::Mat(cvImage))) { @@ -653,5 +601,4 @@ void *YoloObjectDetector::publishInThread() return 0; } - } /* namespace darknet_ros*/ diff --git a/darknet_ros/src/image_interface.c b/darknet_ros/src/image_interface.c index 7fe9d9d53..e1ab068cb 100644 --- a/darknet_ros/src/image_interface.c +++ b/darknet_ros/src/image_interface.c @@ -8,23 +8,22 @@ #include "darknet_ros/image_interface.h" -static float get_pixel(image m, int x, int y, int c) -{ - assert(x < m.w && y < m.h && c < m.c); - return m.data[c*m.h*m.w + y*m.w + x]; +static float get_pixel(image m, int x, int y, int c) { + assert(x < m.w && y < m.h && c < m.c); + return m.data[c * m.h * m.w + y * m.w + x]; } -image **load_alphabet_with_file(char *datafile) { +image** load_alphabet_with_file(char* datafile) { int i, j; const int nsize = 8; - image **alphabets = calloc(nsize, sizeof(image)); + image** alphabets = calloc(nsize, sizeof(image)); char* labels = "/labels/%d_%d.png"; - char * files = (char *) malloc(1 + strlen(datafile)+ strlen(labels) ); + char* files = (char*)malloc(1 + strlen(datafile) + strlen(labels)); strcpy(files, datafile); strcat(files, labels); - for(j = 0; j < nsize; ++j){ + for (j = 0; j < nsize; ++j) { alphabets[j] = calloc(128, sizeof(image)); - for(i = 32; i < 127; ++i){ + for (i = 32; i < 127; ++i) { char buff[256]; sprintf(buff, files, i, j); alphabets[j][i] = load_image_color(buff, 0, 0); @@ -34,19 +33,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, 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(p,x,y,k)*255); - } - } + 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); + } } + } } #endif diff --git a/darknet_ros/src/yolo_object_detector_node.cpp b/darknet_ros/src/yolo_object_detector_node.cpp index e7d4edd05..f8639d423 100644 --- a/darknet_ros/src/yolo_object_detector_node.cpp +++ b/darknet_ros/src/yolo_object_detector_node.cpp @@ -6,8 +6,8 @@ * Institute: ETH Zurich, Robotic Systems Lab */ -#include #include +#include int main(int argc, char** argv) { ros::init(argc, argv, "darknet_ros"); diff --git a/darknet_ros/test/ObjectDetection.cpp b/darknet_ros/test/ObjectDetection.cpp index 412220fe0..4478924fd 100644 --- a/darknet_ros/test/ObjectDetection.cpp +++ b/darknet_ros/test/ObjectDetection.cpp @@ -6,34 +6,33 @@ * Institute: ETH Zurich, Robotic Systems Lab */ - // Google Test #include // ROS -#include +#include #include +#include #include -#include // boost #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; @@ -48,30 +47,25 @@ 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 @@ -86,24 +80,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. @@ -124,25 +115,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)); } } @@ -155,9 +144,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. @@ -175,13 +163,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)); @@ -194,7 +180,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. @@ -210,15 +196,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(); } From f6309fca70ec14d8cc2812e94f318cd755e0f497 Mon Sep 17 00:00:00 2001 From: Tom Lankhorst Date: Tue, 14 Apr 2020 09:58:30 +0200 Subject: [PATCH 04/64] Update package.xml dependencies --- darknet_ros/package.xml | 3 +++ 1 file changed, 3 insertions(+) diff --git a/darknet_ros/package.xml b/darknet_ros/package.xml index 6064ea595..a716e5b7a 100644 --- a/darknet_ros/package.xml +++ b/darknet_ros/package.xml @@ -10,8 +10,11 @@ catkin boost + libopencv-dev + libx11 roscpp + cmake_clang_tools rospy std_msgs image_transport From 8041acd6bdf3532304297fb9d198e9d2d74155de Mon Sep 17 00:00:00 2001 From: Tom Lankhorst Date: Tue, 14 Apr 2020 10:00:21 +0200 Subject: [PATCH 05/64] Don't require cmake-clang-tools --- darknet_ros/package.xml | 1 - 1 file changed, 1 deletion(-) diff --git a/darknet_ros/package.xml b/darknet_ros/package.xml index a716e5b7a..d65a0b410 100644 --- a/darknet_ros/package.xml +++ b/darknet_ros/package.xml @@ -14,7 +14,6 @@ libx11 roscpp - cmake_clang_tools rospy std_msgs image_transport From 0e4bf3e927efe49e30d6af67c1ccf1ac33f8ed5a Mon Sep 17 00:00:00 2001 From: Tom Lankhorst Date: Tue, 14 Apr 2020 18:24:33 +0200 Subject: [PATCH 06/64] Retrieve binaries from Github releases --- darknet_ros/CMakeLists.txt | 6 +++--- 1 file changed, 3 insertions(+), 3 deletions(-) diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index ba2b7f3de..b76f4fa70 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -214,7 +214,7 @@ 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}) + execute_process(COMMAND wget -q https://github.com/leggedrobotics/darknet_ros/releases/download/1.1.4/yolov2-tiny.weights -P ${PATH}) endif() # Download yolov3.weights @@ -222,7 +222,7 @@ 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}) + execute_process(COMMAND wget -q https://github.com/leggedrobotics/darknet_ros/releases/download/1.1.4/yolov3.weights -P ${PATH}) endif() ############# @@ -236,7 +236,7 @@ if(CATKIN_ENABLE_TESTING) 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}) + execute_process(COMMAND wget -q https://github.com/leggedrobotics/darknet_ros/releases/download/1.1.4/yolov2.weights -P ${PATH}) endif() find_package(rostest REQUIRED) From 2c281b51036202afd9aaee82131716d47ef44a05 Mon Sep 17 00:00:00 2001 From: Tom Lankhorst Date: Tue, 14 Apr 2020 18:38:05 +0200 Subject: [PATCH 07/64] Add libxt-dev --- darknet_ros/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/darknet_ros/package.xml b/darknet_ros/package.xml index d65a0b410..6efed62c8 100644 --- a/darknet_ros/package.xml +++ b/darknet_ros/package.xml @@ -12,6 +12,7 @@ boost libopencv-dev libx11 + libxt-dev roscpp rospy From f4c96de20e054bfd23c8b0845ccabf7a95c8d11a Mon Sep 17 00:00:00 2001 From: Tom Lankhorst Date: Tue, 14 Apr 2020 18:41:41 +0200 Subject: [PATCH 08/64] Add libxext --- darknet_ros/package.xml | 1 + 1 file changed, 1 insertion(+) diff --git a/darknet_ros/package.xml b/darknet_ros/package.xml index 6efed62c8..55b2e9370 100644 --- a/darknet_ros/package.xml +++ b/darknet_ros/package.xml @@ -13,6 +13,7 @@ libopencv-dev libx11 libxt-dev + libxext roscpp rospy From 0f702674cba6a88319767fdbe02f168ee04413cf Mon Sep 17 00:00:00 2001 From: timonh Date: Wed, 23 Dec 2020 20:38:55 +0100 Subject: [PATCH 09/64] Adding option to use nodelet --- darknet_ros/CMakeLists.txt | 14 +++++++++ darknet_ros/launch/darknet_ros_nodelet.launch | 30 +++++++++++++++++++ darknet_ros/nodelet_plugins.xml | 8 +++++ darknet_ros/package.xml | 5 ++++ darknet_ros/src/yolo_object_detector_node.cpp | 2 +- .../src/yolo_object_detector_nodelet.cpp | 30 +++++++++++++++++++ 6 files changed, 88 insertions(+), 1 deletion(-) create mode 100644 darknet_ros/launch/darknet_ros_nodelet.launch create mode 100644 darknet_ros/nodelet_plugins.xml create mode 100644 darknet_ros/src/yolo_object_detector_nodelet.cpp diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index b76f4fa70..56fcfba3d 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -58,6 +58,7 @@ find_package(catkin REQUIRED actionlib darknet_ros_msgs image_transport + nodelet ) # Enable OPENCV in darknet @@ -77,6 +78,7 @@ catkin_package( std_msgs darknet_ros_msgs image_transport + nodelet DEPENDS Boost ) @@ -158,6 +160,10 @@ if (CUDA_FOUND) src/yolo_object_detector_node.cpp ) + cuda_add_library(${PROJECT_NAME}_nodelet + src/yolo_object_detector_nodelet.cpp + ) + else() add_library(${PROJECT_NAME}_lib @@ -168,6 +174,10 @@ else() src/yolo_object_detector_node.cpp ) + add_library(${PROJECT_NAME}_nodelet + src/yolo_object_detector_nodelet.cpp + ) + endif() target_link_libraries(${PROJECT_NAME}_lib @@ -184,6 +194,10 @@ target_link_libraries(${PROJECT_NAME} ${PROJECT_NAME}_lib ) +target_link_libraries(${PROJECT_NAME}_nodelet + ${PROJECT_NAME}_lib +) + add_dependencies(${PROJECT_NAME}_lib darknet_ros_msgs_generate_messages_cpp ) diff --git a/darknet_ros/launch/darknet_ros_nodelet.launch b/darknet_ros/launch/darknet_ros_nodelet.launch new file mode 100644 index 000000000..357dfc20b --- /dev/null +++ b/darknet_ros/launch/darknet_ros_nodelet.launch @@ -0,0 +1,30 @@ + + + + + + + + + + + + + + + + + + + + + + + + + + + + + + \ No newline at end of file diff --git a/darknet_ros/nodelet_plugins.xml b/darknet_ros/nodelet_plugins.xml new file mode 100644 index 000000000..8a03b2fd8 --- /dev/null +++ b/darknet_ros/nodelet_plugins.xml @@ -0,0 +1,8 @@ + + + + + Darknet ROS Nodelet. + + + \ No newline at end of file diff --git a/darknet_ros/package.xml b/darknet_ros/package.xml index 55b2e9370..d858a6aeb 100644 --- a/darknet_ros/package.xml +++ b/darknet_ros/package.xml @@ -24,6 +24,11 @@ message_generation darknet_ros_msgs actionlib + nodelet + + + + rostest diff --git a/darknet_ros/src/yolo_object_detector_node.cpp b/darknet_ros/src/yolo_object_detector_node.cpp index f8639d423..d491665d8 100644 --- a/darknet_ros/src/yolo_object_detector_node.cpp +++ b/darknet_ros/src/yolo_object_detector_node.cpp @@ -1,5 +1,5 @@ /* - * yolo_obstacle_detector_node.cpp + * yolo_object_detector_node.cpp * * Created on: Dec 19, 2016 * Author: Marko Bjelonic diff --git a/darknet_ros/src/yolo_object_detector_nodelet.cpp b/darknet_ros/src/yolo_object_detector_nodelet.cpp new file mode 100644 index 000000000..a82faf505 --- /dev/null +++ b/darknet_ros/src/yolo_object_detector_nodelet.cpp @@ -0,0 +1,30 @@ +/* + * yolo_object_detector_nodelet.cpp + * + * Created on: Dec 19, 2016 + * Author: Marko Bjelonic + * Institute: ETH Zurich, Robotic Systems Lab + */ + +#include +#include +#include +#include + +class DarknetRosNodelet : public nodelet::Nodelet { + public: + DarknetRosNodelet() = default; + ~DarknetRosNodelet() = default; + + private: + virtual void onInit() { + ros::NodeHandle NodeHandle("~"); + NodeHandle = getPrivateNodeHandle(); + darknet_ros_ = new darknet_ros::YoloObjectDetector(NodeHandle); + } + + darknet_ros::YoloObjectDetector* darknet_ros_; +}; + +// Declare as a Plug-in +PLUGINLIB_EXPORT_CLASS(DarknetRosNodelet, nodelet::Nodelet); \ No newline at end of file From 2cd3056f17f8eebfbf3de3bde2decfe58416a997 Mon Sep 17 00:00:00 2001 From: timonh Date: Wed, 23 Dec 2020 20:49:35 +0100 Subject: [PATCH 10/64] Minor formatting --- darknet_ros/CMakeLists.txt | 2 ++ darknet_ros/nodelet_plugins.xml | 4 ++-- darknet_ros/package.xml | 9 +++++---- 3 files changed, 9 insertions(+), 6 deletions(-) diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 56fcfba3d..a5bf12021 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -59,6 +59,7 @@ find_package(catkin REQUIRED darknet_ros_msgs image_transport nodelet + ) # Enable OPENCV in darknet @@ -79,6 +80,7 @@ catkin_package( darknet_ros_msgs image_transport nodelet + DEPENDS Boost ) diff --git a/darknet_ros/nodelet_plugins.xml b/darknet_ros/nodelet_plugins.xml index 8a03b2fd8..d5a182fea 100644 --- a/darknet_ros/nodelet_plugins.xml +++ b/darknet_ros/nodelet_plugins.xml @@ -1,8 +1,8 @@ - + - Darknet ROS Nodelet. + Darknet Ros Nodelet. \ No newline at end of file diff --git a/darknet_ros/package.xml b/darknet_ros/package.xml index d858a6aeb..841a80150 100644 --- a/darknet_ros/package.xml +++ b/darknet_ros/package.xml @@ -26,11 +26,12 @@ actionlib nodelet - - - - rostest wget + + + + + From 9e3f70541720aa8acedc9662cc4fb0bd75e651ef Mon Sep 17 00:00:00 2001 From: timonh Date: Mon, 4 Jan 2021 13:07:07 +0100 Subject: [PATCH 11/64] Added pointer deletion in destructor and minor formatting --- darknet_ros/src/yolo_object_detector_nodelet.cpp | 13 ++++++------- 1 file changed, 6 insertions(+), 7 deletions(-) diff --git a/darknet_ros/src/yolo_object_detector_nodelet.cpp b/darknet_ros/src/yolo_object_detector_nodelet.cpp index a82faf505..661157cc1 100644 --- a/darknet_ros/src/yolo_object_detector_nodelet.cpp +++ b/darknet_ros/src/yolo_object_detector_nodelet.cpp @@ -1,8 +1,5 @@ /* - * yolo_object_detector_nodelet.cpp - * - * Created on: Dec 19, 2016 - * Author: Marko Bjelonic + * Author: Marko Bjelonic * Institute: ETH Zurich, Robotic Systems Lab */ @@ -14,16 +11,18 @@ class DarknetRosNodelet : public nodelet::Nodelet { public: DarknetRosNodelet() = default; - ~DarknetRosNodelet() = default; + ~DarknetRosNodelet() { + if (darknetRos_) delete darknetRos_; + } private: virtual void onInit() { ros::NodeHandle NodeHandle("~"); NodeHandle = getPrivateNodeHandle(); - darknet_ros_ = new darknet_ros::YoloObjectDetector(NodeHandle); + darknetRos_ = new darknet_ros::YoloObjectDetector(NodeHandle); } - darknet_ros::YoloObjectDetector* darknet_ros_; + darknet_ros::YoloObjectDetector* darknetRos_; }; // Declare as a Plug-in From 90bbe04a61202f2c790049ecf6850f5cef4bb25e Mon Sep 17 00:00:00 2001 From: timonh Date: Tue, 19 Jan 2021 11:19:42 +0100 Subject: [PATCH 12/64] Small adjustments --- darknet_ros/CMakeLists.txt | 2 -- darknet_ros/src/yolo_object_detector_nodelet.cpp | 2 +- 2 files changed, 1 insertion(+), 3 deletions(-) diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index a5bf12021..56fcfba3d 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -59,7 +59,6 @@ find_package(catkin REQUIRED darknet_ros_msgs image_transport nodelet - ) # Enable OPENCV in darknet @@ -80,7 +79,6 @@ catkin_package( darknet_ros_msgs image_transport nodelet - DEPENDS Boost ) diff --git a/darknet_ros/src/yolo_object_detector_nodelet.cpp b/darknet_ros/src/yolo_object_detector_nodelet.cpp index 661157cc1..5e428bfd1 100644 --- a/darknet_ros/src/yolo_object_detector_nodelet.cpp +++ b/darknet_ros/src/yolo_object_detector_nodelet.cpp @@ -1,5 +1,5 @@ /* - * Author: Marko Bjelonic + * Author: Timon Homberger * Institute: ETH Zurich, Robotic Systems Lab */ From c629f01952390627cdde2f93a719ade2fafceb36 Mon Sep 17 00:00:00 2001 From: Tom Lankhorst Date: Sat, 13 Feb 2021 13:22:48 +0100 Subject: [PATCH 13/64] Use GitHub actions (#300) --- .github/workflows/catkin-build.yml | 44 ++++++++++++++++++++++++++++++ 1 file changed, 44 insertions(+) create mode 100644 .github/workflows/catkin-build.yml diff --git a/.github/workflows/catkin-build.yml b/.github/workflows/catkin-build.yml new file mode 100644 index 000000000..8ba3d5b41 --- /dev/null +++ b/.github/workflows/catkin-build.yml @@ -0,0 +1,44 @@ +name: Build + +on: [push] + +env: + BUILD_TYPE: Release + +jobs: + build: + runs-on: ubuntu-20.04 + container: ros:melodic + + steps: + - name: update git + run: | + apt-get update + apt-get install -y software-properties-common + add-apt-repository ppa:git-core/ppa + apt-get update + apt-get install -y git + + - uses: actions/checkout@v2 + with: + path: src/darknet_ros + submodules: 'recursive' + + - name: rosdep install + run: | + apt-get update + rosdep update + rosdep install --from-paths src --ignore-src -r -y + + - name: catkin_make + shell: bash + run: | + source /opt/ros/$ROS_DISTRO/setup.bash + catkin_make -DCMAKE_BUILD_TYPE=$BUILD_TYPE + + - name: catkin_make run_tests + shell: bash + run: | + source /opt/ros/$ROS_DISTRO/setup.bash + catkin_make run_tests + From b9d9a7dd54321d6ef1d85dcbc6ef5a1f43dc8d2f Mon Sep 17 00:00:00 2001 From: Tom Lankhorst Date: Sat, 13 Feb 2021 16:00:06 +0100 Subject: [PATCH 14/64] catkin_test_results (#302) --- .github/workflows/catkin-build.yml | 1 + 1 file changed, 1 insertion(+) diff --git a/.github/workflows/catkin-build.yml b/.github/workflows/catkin-build.yml index 8ba3d5b41..efa6eff28 100644 --- a/.github/workflows/catkin-build.yml +++ b/.github/workflows/catkin-build.yml @@ -41,4 +41,5 @@ jobs: run: | source /opt/ros/$ROS_DISTRO/setup.bash catkin_make run_tests + catkin_test_results From 0f1328b2a14e84397c5781c06bf66fdbfa8574c4 Mon Sep 17 00:00:00 2001 From: Marko Bjelonic Date: Thu, 8 Apr 2021 10:25:11 +0200 Subject: [PATCH 15/64] First changes in CMakeLists. --- darknet_ros/CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 56fcfba3d..17e388b45 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -1,8 +1,8 @@ -cmake_minimum_required(VERSION 2.8.12) +cmake_minimum_required(VERSION 3.5.1) project(darknet_ros) # Set c++11 cmake flags -set(CMAKE_CXX_FLAGS "-std=c++11 ${CMAKE_CXX_FLAGS}") +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) From 078cdfd6bd019be8e53514c24abb7c70d1b4a77e Mon Sep 17 00:00:00 2001 From: Marko Bjelonic Date: Thu, 8 Apr 2021 12:54:30 +0200 Subject: [PATCH 16/64] Updated to newest darknet and fixed opencv on Ubuntu 20.04. --- darknet | 2 +- darknet_ros/CMakeLists.txt | 12 +++---- .../darknet_ros/YoloObjectDetector.hpp | 19 +++++----- ...{image_interface.h => image_interface.hpp} | 3 +- darknet_ros/src/YoloObjectDetector.cpp | 35 ++++++++----------- ...{image_interface.c => image_interface.cpp} | 12 +++---- darknet_ros/test/ObjectDetection.cpp | 2 +- 7 files changed, 39 insertions(+), 46 deletions(-) rename darknet_ros/include/darknet_ros/{image_interface.h => image_interface.hpp} (81%) rename darknet_ros/src/{image_interface.c => image_interface.cpp} (74%) diff --git a/darknet b/darknet index 508381b37..17d47744a 160000 --- a/darknet +++ b/darknet @@ -1 +1 @@ -Subproject commit 508381b37fe75e0e1a01bcb2941cb0b31eb0e4c9 +Subproject commit 17d47744a290a6d95f9f4d592e8955b5baa8615f diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 17e388b45..807b0e571 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -23,12 +23,7 @@ if (CUDA_FOUND) 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) else() @@ -92,7 +87,7 @@ include_directories( ) set(PROJECT_LIB_FILES - src/YoloObjectDetector.cpp src/image_interface.c + src/YoloObjectDetector.cpp src/image_interface.cpp ) set(DARKNET_CORE_FILES @@ -118,16 +113,17 @@ set(DARKNET_CORE_FILES ${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/attention.c ${DARKNET_PATH}/examples/nightmare.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}/examples/go.c ${DARKNET_PATH}/examples/go.c ) set(DARKNET_CUDA_FILES diff --git a/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp b/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp index daef6ef67..304b09395 100644 --- a/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp +++ b/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp @@ -49,7 +49,6 @@ extern "C" { #include #include "box.h" #include "cost_layer.h" -#include "darknet_ros/image_interface.h" #include "detection_layer.h" #include "network.h" #include "parser.h" @@ -57,9 +56,12 @@ extern "C" { #include "utils.h" } -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); +// Image interface. +#include "darknet_ros/image_interface.hpp" + +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); namespace darknet_ros { @@ -70,9 +72,9 @@ typedef struct { } RosBox_; typedef struct { - IplImage* image; + cv::Mat image; std_msgs::Header header; -} IplImageWithHeader_; +} CvMatWithHeader_; class YoloObjectDetector { public: @@ -174,12 +176,11 @@ class YoloObjectDetector { image buffLetter_[3]; int buffId_[3]; int buffIndex_ = 0; - IplImage* ipl_; float fps_ = 0; float demoThresh_ = 0; float demoHier_ = .5; int running_ = 0; - + cv::Mat disp_; int demoDelay_ = 0; int demoFrame_ = 3; float** predictions_; @@ -234,7 +235,7 @@ class YoloObjectDetector { void yolo(); - IplImageWithHeader_ getIplImageWithHeader(); + CvMatWithHeader_ getCvMatWithHeader(); bool getImageStatus(void); diff --git a/darknet_ros/include/darknet_ros/image_interface.h b/darknet_ros/include/darknet_ros/image_interface.hpp similarity index 81% rename from darknet_ros/include/darknet_ros/image_interface.h rename to darknet_ros/include/darknet_ros/image_interface.hpp index 7fb3d49b1..705bff602 100644 --- a/darknet_ros/include/darknet_ros/image_interface.h +++ b/darknet_ros/include/darknet_ros/image_interface.hpp @@ -10,9 +10,10 @@ #define IMAGE_INTERFACE_H #include "image.h" +#include "opencv2/opencv.hpp" 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 diff --git a/darknet_ros/src/YoloObjectDetector.cpp b/darknet_ros/src/YoloObjectDetector.cpp index 17cb41e7a..966972ace 100644 --- a/darknet_ros/src/YoloObjectDetector.cpp +++ b/darknet_ros/src/YoloObjectDetector.cpp @@ -368,9 +368,8 @@ void* YoloObjectDetector::detectInThread() { void* YoloObjectDetector::fetchInThread() { { boost::shared_lock lock(mutexImageCallback_); - IplImageWithHeader_ imageAndHeader = getIplImageWithHeader(); - IplImage* ROS_img = imageAndHeader.image; - ipl_into_image(ROS_img, buff_[buffIndex_]); + CvMatWithHeader_ imageAndHeader = getCvMatWithHeader(); + buff_[buffIndex_] = mat_to_image(imageAndHeader.image); headerBuff_[buffIndex_] = imageAndHeader.header; buffId_[buffIndex_] = actionId_; } @@ -380,8 +379,7 @@ void* YoloObjectDetector::fetchInThread() { } void* YoloObjectDetector::displayInThread(void* ptr) { - show_image_cv(buff_[(buffIndex_ + 1) % 3], "YOLO V3", ipl_); - int c = cv::waitKey(waitKeyDelay_); + int c = show_image(buff_[(buffIndex_ + 1) % 3], "YOLO", 1); if (c != -1) c = c % 256; if (c == 27) { demoDone_ = 1; @@ -424,7 +422,7 @@ void YoloObjectDetector::setupNetwork(char* cfgfile, char* weightfile, char* dat demoThresh_ = thresh; demoHier_ = hier; fullScreen_ = fullscreen; - printf("YOLO V3\n"); + printf("YOLO\n"); net_ = load_network(cfgfile, weightfile, 0); set_batch_network(net_, 1); } @@ -457,9 +455,8 @@ void YoloObjectDetector::yolo() { { boost::shared_lock lock(mutexImageCallback_); - IplImageWithHeader_ imageAndHeader = getIplImageWithHeader(); - IplImage* ROS_img = imageAndHeader.image; - buff_[0] = ipl_to_image(ROS_img); + CvMatWithHeader_ imageAndHeader = getCvMatWithHeader(); + buff_[0] = mat_to_image(imageAndHeader.image); headerBuff_[0] = imageAndHeader.header; } buff_[1] = copy_image(buff_[0]); @@ -469,17 +466,16 @@ 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); + disp_ = image_to_mat(buff_[0]); int count = 0; - if (!demoPrefix_ && viewImage_) { - cv::namedWindow("YOLO V3", cv::WINDOW_NORMAL); + cv::namedWindow("YOLO", cv::WINDOW_NORMAL); if (fullScreen_) { - cv::setWindowProperty("YOLO V3", cv::WND_PROP_FULLSCREEN, cv::WINDOW_FULLSCREEN); + cv::setWindowProperty("YOLO", cv::WND_PROP_FULLSCREEN, cv::WINDOW_FULLSCREEN); } else { - cv::moveWindow("YOLO V3", 0, 0); - cv::resizeWindow("YOLO V3", 640, 480); + cv::moveWindow("YOLO", 0, 0); + cv::resizeWindow("YOLO", 640, 480); } } @@ -495,7 +491,7 @@ void YoloObjectDetector::yolo() { if (viewImage_) { displayInThread(0); } else { - generate_image(buff_[(buffIndex_ + 1) % 3], ipl_); + generate_image(buff_[(buffIndex_ + 1) % 3], disp_); } publishInThread(); } else { @@ -512,9 +508,8 @@ void YoloObjectDetector::yolo() { } } -IplImageWithHeader_ YoloObjectDetector::getIplImageWithHeader() { - IplImage* ROS_img = new IplImage(camImageCopy_); - IplImageWithHeader_ header = {.image = ROS_img, .header = imageHeader_}; +CvMatWithHeader_ YoloObjectDetector::getCvMatWithHeader() { + CvMatWithHeader_ header = {.image = camImageCopy_, .header = imageHeader_}; return header; } @@ -530,7 +525,7 @@ bool YoloObjectDetector::isNodeRunning(void) { void* YoloObjectDetector::publishInThread() { // Publish image. - cv::Mat cvImage = cv::cvarrToMat(ipl_); + cv::Mat cvImage = disp_; if (!publishDetectionImage(cv::Mat(cvImage))) { ROS_DEBUG("Detection image has not been broadcasted."); } diff --git a/darknet_ros/src/image_interface.c b/darknet_ros/src/image_interface.cpp similarity index 74% rename from darknet_ros/src/image_interface.c rename to darknet_ros/src/image_interface.cpp index e1ab068cb..d5dde86ad 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) { assert(x < m.w && y < m.h && c < m.c); @@ -16,13 +16,13 @@ static float get_pixel(image m, int x, int y, int c) { image** load_alphabet_with_file(char* datafile) { int i, j; const int nsize = 8; - image** alphabets = calloc(nsize, sizeof(image)); + image** alphabets = (image**)calloc(nsize, sizeof(image)); char* labels = "/labels/%d_%d.png"; char* files = (char*)malloc(1 + strlen(datafile) + strlen(labels)); strcpy(files, datafile); strcat(files, labels); for (j = 0; j < nsize; ++j) { - alphabets[j] = calloc(128, sizeof(image)); + alphabets[j] = (image*)calloc(128, sizeof(image)); for (i = 32; i < 127; ++i) { char buff[256]; sprintf(buff, files, i, j); @@ -33,16 +33,16 @@ image** load_alphabet_with_file(char* datafile) { } #ifdef OPENCV -void generate_image(image p, IplImage* disp) { +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; + 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->imageData[y * step + x * p.c + k] = (unsigned char)(get_pixel(p, x, y, k) * 255); + disp.data[y * step + x * p.c + k] = (unsigned char)(get_pixel(p, x, y, k) * 255); } } } diff --git a/darknet_ros/test/ObjectDetection.cpp b/darknet_ros/test/ObjectDetection.cpp index 4478924fd..f662a7bf1 100644 --- a/darknet_ros/test/ObjectDetection.cpp +++ b/darknet_ros/test/ObjectDetection.cpp @@ -70,7 +70,7 @@ bool sendImageToYolo(ros::NodeHandle nh, const std::string& pathToTestImage) { // 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(); From 2049ed612c52fba44ec45004cc1a7160abb78151 Mon Sep 17 00:00:00 2001 From: Marko Bjelonic Date: Thu, 8 Apr 2021 14:05:15 +0200 Subject: [PATCH 17/64] Changed submodule url. --- .gitmodules | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.gitmodules b/.gitmodules index 000b92b76..7e7bece16 100644 --- a/.gitmodules +++ b/.gitmodules @@ -1,3 +1,3 @@ [submodule "darknet"] path = darknet - url = https://github.com/pjreddie/darknet + url = https://github.com/leggedrobotics/darknet From 535ab157051eff100637bab40a333bf8daa5643c Mon Sep 17 00:00:00 2001 From: Marko Bjelonic Date: Thu, 8 Apr 2021 14:09:56 +0200 Subject: [PATCH 18/64] Updated commit destination. --- darknet | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/darknet b/darknet index 17d47744a..d22bbf38b 160000 --- a/darknet +++ b/darknet @@ -1 +1 @@ -Subproject commit 17d47744a290a6d95f9f4d592e8955b5baa8615f +Subproject commit d22bbf38bd012f13d2b50c8d98149cd4a9889b7a From e4693eb5fa765bc2e5c0d8d56577b1cdda695c43 Mon Sep 17 00:00:00 2001 From: Marko Bjelonic Date: Thu, 8 Apr 2021 14:15:16 +0200 Subject: [PATCH 19/64] Updated readme. --- README.md | 2 +- darknet_ros/CMakeLists.txt | 5 +++++ 2 files changed, 6 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 68baa0cc1..b687b5170 100644 --- a/README.md +++ b/README.md @@ -4,7 +4,7 @@ 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 Melodic and Ubuntu 18.04. 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 (Please check the branches for melodic, foxy, and ROS2 versions). 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** diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 807b0e571..919eb3b87 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -23,7 +23,12 @@ if (CUDA_FOUND) 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) else() From 973f6683911e6081fdd714f019bd2be70e1d91f1 Mon Sep 17 00:00:00 2001 From: Marko Bjelonic Date: Thu, 8 Apr 2021 14:37:59 +0200 Subject: [PATCH 20/64] Minor fix in test. --- darknet_ros/test/ObjectDetection.cpp | 3 ++- 1 file changed, 2 insertions(+), 1 deletion(-) diff --git a/darknet_ros/test/ObjectDetection.cpp b/darknet_ros/test/ObjectDetection.cpp index f662a7bf1..e1601300f 100644 --- a/darknet_ros/test/ObjectDetection.cpp +++ b/darknet_ros/test/ObjectDetection.cpp @@ -154,7 +154,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)); From 6f53ddc33ee224f8b2e9824b0bc04350f4896e87 Mon Sep 17 00:00:00 2001 From: Marko Bjelonic Date: Thu, 8 Apr 2021 14:46:27 +0200 Subject: [PATCH 21/64] Minor change in Readme. --- README.md | 6 ++++-- 1 file changed, 4 insertions(+), 2 deletions(-) diff --git a/README.md b/README.md index b687b5170..4432a5f9b 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 Noetic and Ubuntu 20.04 (Please check the branches for melodic, foxy, and ROS2 versions). 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** From d8514fb565753a4322649d7b735f2fac56187373 Mon Sep 17 00:00:00 2001 From: Marko Bjelonic Date: Thu, 8 Apr 2021 14:54:03 +0200 Subject: [PATCH 22/64] Minor fix in CMake. --- darknet_ros/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 919eb3b87..9a7be7da5 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -128,7 +128,7 @@ set(DARKNET_CORE_FILES ${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}/examples/go.c + ${DARKNET_PATH}/examples/go.c ) set(DARKNET_CUDA_FILES From 0da88d525ffbd2f308f0a13840ce629079fda33a Mon Sep 17 00:00:00 2001 From: Marko Bjelonic Date: Thu, 8 Apr 2021 21:14:41 +0200 Subject: [PATCH 23/64] Changelog 1.1.5 --- darknet_ros/CHANGELOG.rst | 48 ++++++++++++++++++++++++++++++++++ darknet_ros/package.xml | 2 +- darknet_ros_msgs/CHANGELOG.rst | 10 +++++++ 3 files changed, 59 insertions(+), 1 deletion(-) 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/package.xml b/darknet_ros/package.xml index 841a80150..76a83cef7 100644 --- a/darknet_ros/package.xml +++ b/darknet_ros/package.xml @@ -33,5 +33,5 @@ - + 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) ------------------ From 51aa3387cf4c3a17fbdb4a09dfc8c01710a928f2 Mon Sep 17 00:00:00 2001 From: Marko Bjelonic Date: Thu, 8 Apr 2021 21:14:54 +0200 Subject: [PATCH 24/64] 1.1.5 --- darknet_ros/package.xml | 2 +- darknet_ros_msgs/package.xml | 2 +- 2 files changed, 2 insertions(+), 2 deletions(-) diff --git a/darknet_ros/package.xml b/darknet_ros/package.xml index 76a83cef7..5495933c9 100644 --- a/darknet_ros/package.xml +++ b/darknet_ros/package.xml @@ -1,7 +1,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_msgs/package.xml b/darknet_ros_msgs/package.xml index 54e2df09c..b547746d8 100644 --- a/darknet_ros_msgs/package.xml +++ b/darknet_ros_msgs/package.xml @@ -1,7 +1,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 From 9bed9580ac65a1af7098f435dff65329897a9662 Mon Sep 17 00:00:00 2001 From: Tom Lankhorst Date: Thu, 8 Apr 2021 22:27:19 +0200 Subject: [PATCH 25/64] Update catkin-build.yml --- .github/workflows/catkin-build.yml | 5 ++++- 1 file changed, 4 insertions(+), 1 deletion(-) diff --git a/.github/workflows/catkin-build.yml b/.github/workflows/catkin-build.yml index efa6eff28..c37dc9fc4 100644 --- a/.github/workflows/catkin-build.yml +++ b/.github/workflows/catkin-build.yml @@ -7,8 +7,11 @@ env: jobs: build: + strategy: + matrix: + container: [ros:melodic, ros:noetic] runs-on: ubuntu-20.04 - container: ros:melodic + container: ${{ matrix.container }} steps: - name: update git From 409c01dcce62ead404c612e9646dca721e8ae570 Mon Sep 17 00:00:00 2001 From: Tom Lankhorst Date: Thu, 8 Apr 2021 22:28:22 +0200 Subject: [PATCH 26/64] Quote container names --- .github/workflows/catkin-build.yml | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/.github/workflows/catkin-build.yml b/.github/workflows/catkin-build.yml index c37dc9fc4..6ae7d56a8 100644 --- a/.github/workflows/catkin-build.yml +++ b/.github/workflows/catkin-build.yml @@ -9,7 +9,7 @@ jobs: build: strategy: matrix: - container: [ros:melodic, ros:noetic] + container: ["ros:melodic", "ros:noetic"] runs-on: ubuntu-20.04 container: ${{ matrix.container }} From 2996594316a6ebb4b60b6e860bf0524ed794a6d5 Mon Sep 17 00:00:00 2001 From: Marko Bjelonic Date: Mon, 3 May 2021 09:43:55 +0200 Subject: [PATCH 27/64] One line of code fixes everything! --- darknet_ros/launch/darknet_ros_valgrind.launch | 13 +++++++++++++ darknet_ros/src/YoloObjectDetector.cpp | 1 + 2 files changed, 14 insertions(+) create mode 100644 darknet_ros/launch/darknet_ros_valgrind.launch diff --git a/darknet_ros/launch/darknet_ros_valgrind.launch b/darknet_ros/launch/darknet_ros_valgrind.launch new file mode 100644 index 000000000..64f70f583 --- /dev/null +++ b/darknet_ros/launch/darknet_ros_valgrind.launch @@ -0,0 +1,13 @@ + + + + + + + + + + + + + diff --git a/darknet_ros/src/YoloObjectDetector.cpp b/darknet_ros/src/YoloObjectDetector.cpp index 966972ace..7248a1daf 100644 --- a/darknet_ros/src/YoloObjectDetector.cpp +++ b/darknet_ros/src/YoloObjectDetector.cpp @@ -369,6 +369,7 @@ void* YoloObjectDetector::fetchInThread() { { boost::shared_lock lock(mutexImageCallback_); CvMatWithHeader_ imageAndHeader = getCvMatWithHeader(); + free_image(buff_[buffIndex_]); buff_[buffIndex_] = mat_to_image(imageAndHeader.image); headerBuff_[buffIndex_] = imageAndHeader.header; buffId_[buffIndex_] = actionId_; From 43ce723bdb8c3f8895630f70f48694ccceb606c0 Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Sat, 8 May 2021 20:20:48 +0900 Subject: [PATCH 28/64] April8 --- .gitignore | 2 + .gitmodules | 4 +- darknet | 2 +- darknet_ros/CMakeLists.txt | 95 +++--- .../darknet_ros/YoloObjectDetector.hpp | 46 ++- ...{image_interface.h => image_interface.hpp} | 7 +- darknet_ros/launch/darknet_ros.launch.py | 4 +- darknet_ros/src/YoloObjectDetector.cpp | 304 +++++++++++------- ...{image_interface.c => image_interface.cpp} | 31 +- 9 files changed, 302 insertions(+), 193 deletions(-) create mode 100644 .gitignore rename darknet_ros/include/darknet_ros/{image_interface.h => image_interface.hpp} (71%) rename darknet_ros/src/{image_interface.c => image_interface.cpp} (64%) 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..59e18b078 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 \ No newline at end of file diff --git a/darknet b/darknet index 508381b37..e2a128737 160000 --- a/darknet +++ b/darknet @@ -1 +1 @@ -Subproject commit 508381b37fe75e0e1a01bcb2941cb0b31eb0e4c9 +Subproject commit e2a128737bcee224088a0076629983e2a4beca01 diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 56dbad55a..9dd4a33cc 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -20,8 +20,8 @@ if (CUDA_FOUND) CUDA_NVCC_FLAGS ${CUDA_NVCC_FLAGS}; -O3 - -gencode arch=compute_30,code=sm_30 - -gencode arch=compute_35,code=sm_35 + # -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 @@ -76,55 +76,66 @@ 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/yolo_v2_class.cpp + # ${DARKNET_PATH}/src/yolo_console_dll.cpp ) 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) @@ -186,7 +197,7 @@ target_compile_definitions(${PROJECT_NAME}_lib PRIVATE -DOPENCV) target_link_libraries(${PROJECT_NAME} ${PROJECT_NAME}_lib - ${PROJECT_NAME}_core_lib + # ${PROJECT_NAME}_core_lib ) target_compile_definitions(${PROJECT_NAME} PRIVATE -DOPENCV) @@ -201,6 +212,7 @@ install( DIRECTORY include/ DESTINATION include/ FILES_MATCHING PATTERN "*.h" + # FILES_MATCHING PATTERN "*.hpp" ) # Download yolov2-tiny.weights @@ -255,6 +267,7 @@ endif() ament_export_include_directories(include) ament_export_libraries(${PROJECT_NAME}_lib) +ament_export_libraries(${PROJECT_NAME}_core_lib) ament_export_dependencies(${dependencies}) ament_package() \ 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..215770887 100644 --- a/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp +++ b/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp @@ -53,13 +53,29 @@ 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 "darknet_ros/image_interface.hpp" + #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" 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 +86,16 @@ typedef struct int num, Class; } RosBox_; -typedef struct -{ - IplImage* image; +// typedef struct +// { +// IplImage* image; +// std_msgs::msg::Header header; +// } IplImageWithHeader_; + +typedef struct { + cv::Mat image; std_msgs::msg::Header header; -} IplImageWithHeader_; +} CvMatWithHeader; class YoloObjectDetector : public rclcpp::Node { @@ -187,7 +208,8 @@ class YoloObjectDetector : public rclcpp::Node image buffLetter_[3]; int buffId_[3]; int buffIndex_ = 0; - IplImage * ipl_; + // IplImage * ipl_; + cv::Mat disp_; float fps_ = 0; float demoThresh_ = 0; float demoHier_ = .5; @@ -249,13 +271,17 @@ class YoloObjectDetector : public rclcpp::Node void yolo(); - IplImageWithHeader_ getIplImageWithHeader(); + // IplImageWithHeader_ getIplImageWithHeader(); + CvMatWithHeader getCvMatWithHeader(); bool getImageStatus(void); bool isNodeRunning(void); void *publishInThread(); + + void generate_image(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 71% rename from darknet_ros/include/darknet_ros/image_interface.h rename to darknet_ros/include/darknet_ros/image_interface.hpp index 2aa1353a3..5bdcd2a8d 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,7 @@ 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, IplImage *disp); +// void generate_image(image p, cv::Mat& disp); #endif diff --git a/darknet_ros/launch/darknet_ros.launch.py b/darknet_ros/launch/darknet_ros.launch.py index 0cd39ecb2..4d0c3c08f 100644 --- a/darknet_ros/launch/darknet_ros.launch.py +++ b/darknet_ros/launch/darknet_ros.launch.py @@ -11,7 +11,7 @@ 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') @@ -19,7 +19,7 @@ def generate_launch_description(): 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', diff --git a/darknet_ros/src/YoloObjectDetector.cpp b/darknet_ros/src/YoloObjectDetector.cpp index 67d5c3b41..774d1a721 100644 --- a/darknet_ros/src/YoloObjectDetector.cpp +++ b/darknet_ros/src/YoloObjectDetector.cpp @@ -371,7 +371,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 +380,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; @@ -398,8 +400,9 @@ void *YoloObjectDetector::detectInThread() 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_cv_v3(show_img, dets, nboxes, demoThresh_, demoNames_, demoAlphabet_, demoClasses_, 0); // extract the bounding boxes and send them to ROS int i, j; int count = 0; @@ -456,31 +459,45 @@ void *YoloObjectDetector::detectInThread() } -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 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_]); +// headerBuff_[buffIndex_] = imageAndHeader.header; +// buffId_[buffIndex_] = actionId_; +// } +// rgbgr_image(buff_[buffIndex_]); +// letterbox_image_into(buff_[buffIndex_], net_->w, net_->h, buffLetter_[buffIndex_]); +// return 0; +// } + +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 +515,86 @@ 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 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_); - int c = cv::waitKey(waitKeyDelay_); - if (c != -1) c = c%256; - if (c == 27) { - demoDone_ = 1; - return 0; - } else if (c == 82) { - demoThresh_ += .02; - } else if (c == 84) { - demoThresh_ -= .02; - if(demoThresh_ <= .02) demoThresh_ = .02; - } else if (c == 83) { - demoHier_ += .02; - } else if (c == 81) { - demoHier_ -= .02; - if(demoHier_ <= .0) demoHier_ = .0; - } +// void *YoloObjectDetector::displayInThread(void *ptr) +// { +// show_image_cv_cp(buff_[(buffIndex_ + 1)%3], "YOLO V3", ipl_); +// int c = cv::waitKey(waitKeyDelay_); +// if (c != -1) c = c%256; +// if (c == 27) { +// demoDone_ = 1; +// return 0; +// } else if (c == 82) { +// demoThresh_ += .02; +// } else if (c == 84) { +// demoThresh_ -= .02; +// if(demoThresh_ <= .02) demoThresh_ = .02; +// } else if (c == 83) { +// demoHier_ += .02; +// } else if (c == 81) { +// demoHier_ -= .02; +// if(demoHier_ <= .0) demoHier_ = .0; +// } +// return 0; +// } + +void* YoloObjectDetector::displayInThread(void* ptr) { + show_image(buff_[(buffIndex_ + 1) % 3], "YOLO"); + // int c = show_image_cv(buff_[(buffIndex_ + 1) % 3], "YOLO"); + // if (c != -1) c = c % 256; + // if (c == 27) { + // demoDone_ = 1; + // return 0; + // } else if (c == 82) { + // demoThresh_ += .02; + // } else if (c == 84) { + // demoThresh_ -= .02; + // if (demoThresh_ <= .02) demoThresh_ = .02; + // } else if (c == 83) { + // demoHier_ += .02; + // } else if (c == 81) { + // demoHier_ -= .02; + // if (demoHier_ <= .0) demoHier_ = .0; + // } return 0; } + void *YoloObjectDetector::displayLoop(void *ptr) { while (1) { @@ -610,31 +649,31 @@ 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); - } - } - } -} +// void generate_image_cp(image p, IplImage *disp) -> generate_image +// { +// 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; -} +// 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() { @@ -663,13 +702,16 @@ void YoloObjectDetector::yolo() layer l = net_->layers[net_->n - 1]; roiBoxes_ = (darknet_ros::RosBox_ *) calloc(l.w * l.h * l.n, sizeof(darknet_ros::RosBox_)); - { - std::shared_lock lock(mutexImageCallback_); - IplImageWithHeader_ imageAndHeader = getIplImageWithHeader(); - IplImage* ROS_img = imageAndHeader.image; - buff_[0] = ipl_to_image_cp(ROS_img); - headerBuff_[0] = imageAndHeader.header; - } + + std::shared_lock lock(mutexImageCallback_); + // IplImageWithHeader_ imageAndHeader = getIplImageWithHeader(); + // IplImage* ROS_img = imageAndHeader.image; + // buff_[0] = ipl_to_image_cp(ROS_img); + // boost::shared_lock lock(mutexImageCallback_); //for boost + CvMatWithHeader imageAndHeader = getCvMatWithHeader(); + buff_[0] = mat_to_image(imageAndHeader.image); + headerBuff_[0] = imageAndHeader.header; + buff_[1] = copy_image(buff_[0]); buff_[2] = copy_image(buff_[0]); headerBuff_[1] = headerBuff_[0]; @@ -677,7 +719,9 @@ 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); + // 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; @@ -703,7 +747,8 @@ void YoloObjectDetector::yolo() if (viewImage_) { displayInThread(0); } else { - generate_image_cp(buff_[(buffIndex_ + 1)%3], ipl_); + // generate_image_cp(buff_[(buffIndex_ + 1)%3], ipl_); + generate_image(buff_[(buffIndex_ + 1) % 3], disp_); } publishInThread(); } else { @@ -721,11 +766,16 @@ void YoloObjectDetector::yolo() } -IplImageWithHeader_ YoloObjectDetector::getIplImageWithHeader() -{ - IplImage* ROS_img = new IplImage(); - *ROS_img = cvIplImage(camImageCopy_); - IplImageWithHeader_ header = {.image = ROS_img, .header = imageHeader_}; +// IplImageWithHeader_ YoloObjectDetector::getIplImageWithHeader() +// { +// IplImage* ROS_img = new IplImage(); +// *ROS_img = cvIplImage(camImageCopy_); +// IplImageWithHeader_ header = {.image = ROS_img, .header = imageHeader_}; +// return header; +// } + +CvMatWithHeader YoloObjectDetector::getCvMatWithHeader() { + CvMatWithHeader header = {.image = camImageCopy_, .header = imageHeader_}; return header; } @@ -744,7 +794,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 +868,20 @@ void *YoloObjectDetector::publishInThread() return 0; } +void YoloObjectDetector::generate_image(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 64% rename from darknet_ros/src/image_interface.c rename to darknet_ros/src/image_interface.cpp index 8ee77cd43..4c7636f90 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,20 @@ 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, 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(p,x,y,k)*255); - } - } - } -} +// 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); +// } +// } +// } +// } +// #endif From d58a2ac59eb7cb15cf352a5b6a02915252359c73 Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Sun, 9 May 2021 19:04:10 +0900 Subject: [PATCH 29/64] ipl to cv --- darknet_ros/CMakeLists.txt | 8 + darknet_ros/config/yolov4.yaml | 91 ++ .../darknet_ros/YoloObjectDetector.hpp | 18 +- darknet_ros/launch/darknet_ros.launch.py | 4 +- darknet_ros/launch/yolov4.launch.py | 63 + darknet_ros/src/YoloObjectDetector.cpp | 208 +-- .../yolo_network_config/cfg/yolov4.cfg | 1160 +++++++++++++++++ 7 files changed, 1361 insertions(+), 191 deletions(-) create mode 100644 darknet_ros/config/yolov4.yaml create mode 100644 darknet_ros/launch/yolov4.launch.py create mode 100644 darknet_ros/yolo_network_config/cfg/yolov4.cfg diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 9dd4a33cc..e2b35d77f 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -235,6 +235,14 @@ endif() install(DIRECTORY yolo_network_config/cfg yolo_network_config/weights DESTINATION share/${PROJECT_NAME}/yolo_network_config/) install(DIRECTORY launch config DESTINATION share/${PROJECT_NAME}/) +# 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 ## ############# diff --git a/darknet_ros/config/yolov4.yaml b/darknet_ros/config/yolov4.yaml new file mode 100644 index 000000000..89ed16da5 --- /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/include/darknet_ros/YoloObjectDetector.hpp b/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp index 215770887..283a2d45b 100644 --- a/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp +++ b/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp @@ -65,15 +65,11 @@ extern "C" { #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 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 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); @@ -86,16 +82,10 @@ typedef struct int num, Class; } RosBox_; -// typedef struct -// { -// IplImage* image; -// std_msgs::msg::Header header; -// } IplImageWithHeader_; - typedef struct { cv::Mat image; std_msgs::msg::Header header; -} CvMatWithHeader; +} CvMatWithHeader_; class YoloObjectDetector : public rclcpp::Node { @@ -272,7 +262,7 @@ class YoloObjectDetector : public rclcpp::Node void yolo(); // IplImageWithHeader_ getIplImageWithHeader(); - CvMatWithHeader getCvMatWithHeader(); + CvMatWithHeader_ getCvMatWithHeader(); bool getImageStatus(void); diff --git a/darknet_ros/launch/darknet_ros.launch.py b/darknet_ros/launch/darknet_ros.launch.py index 4d0c3c08f..689c1a9fe 100644 --- a/darknet_ros/launch/darknet_ros.launch.py +++ b/darknet_ros/launch/darknet_ros.launch.py @@ -15,7 +15,7 @@ def generate_launch_description(): 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/yolov3.yaml') declare_image_cmd = DeclareLaunchArgument( 'image', @@ -35,7 +35,7 @@ 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', + default_value = darknet_ros_share_dir + '/config/yolov3.yaml', description = 'Path to file with network param file') darknet_ros_cmd = Node( diff --git a/darknet_ros/launch/yolov4.launch.py b/darknet_ros/launch/yolov4.launch.py new file mode 100644 index 000000000..0591d5afe --- /dev/null +++ b/darknet_ros/launch/yolov4.launch.py @@ -0,0 +1,63 @@ +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, SetEnvironmentVariable +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node + +def generate_launch_description(): + darknet_ros_share_dir = get_package_share_directory('darknet_ros') + + 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/yolov4.yaml') + + declare_image_cmd = DeclareLaunchArgument( + 'image', + 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') + declare_yolo_config_path_cmd = DeclareLaunchArgument( + 'yolo_config_path', + default_value = darknet_ros_share_dir + '/yolo_network_config/cfg', + description = 'Path to yolo config') + declare_ros_param_file_cmd = DeclareLaunchArgument( + 'ros_param_file', + default_value = darknet_ros_share_dir + '/config/ros.yaml', + description = 'Path to file with ROS related config') + declare_network_param_file_cmd = DeclareLaunchArgument( + 'network_param_file', + default_value = darknet_ros_share_dir + '/config/yolov4.yaml', + description = 'Path to file with network param file') + + darknet_ros_cmd = Node( + package='darknet_ros', + node_executable='darknet_ros', + node_name='darknet_ros', + output='screen', + parameters=[ros_param_file, network_param_file, + { + "config_path": yolo_config_path, + "weights_path": yolo_weights_path, + }, + ]) + + ld = LaunchDescription() + + ld.add_action(declare_image_cmd) + ld.add_action(declare_yolo_weights_path_cmd) + ld.add_action(declare_yolo_config_path_cmd) + ld.add_action(declare_ros_param_file_cmd) + ld.add_action(declare_network_param_file_cmd) + + ld.add_action(darknet_ros_cmd) + + return ld diff --git a/darknet_ros/src/YoloObjectDetector.cpp b/darknet_ros/src/YoloObjectDetector.cpp index 774d1a721..a1a503f52 100644 --- a/darknet_ros/src/YoloObjectDetector.cpp +++ b/darknet_ros/src/YoloObjectDetector.cpp @@ -321,15 +321,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; @@ -380,7 +371,7 @@ void *YoloObjectDetector::detectInThread() { running_ = 1; float nms = .4; - mat_cv* show_img = NULL; + // mat_cv* show_img = NULL; layer l = net_->layers[net_->n - 1]; float *X = buffLetter_[(buffIndex_ + 2) % 3].data; @@ -402,7 +393,7 @@ void *YoloObjectDetector::detectInThread() image display = buff_[(buffIndex_+2) % 3]; // draw_detections(display, dets, nboxes, demoThresh_, demoNames_, demoAlphabet_, demoClasses_); - draw_detections_cv_v3(show_img, dets, nboxes, demoThresh_, demoNames_, demoAlphabet_, demoClasses_, 0); + 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; @@ -458,44 +449,10 @@ 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() -// { -// { -// std::shared_lock lock(mutexImageCallback_); -// IplImageWithHeader_ imageAndHeader = getIplImageWithHeader(); -// IplImage* ROS_img = imageAndHeader.image; -// ipl_into_image_cp(ROS_img, buff_[buffIndex_]); -// headerBuff_[buffIndex_] = imageAndHeader.header; -// buffId_[buffIndex_] = actionId_; -// } -// rgbgr_image(buff_[buffIndex_]); -// letterbox_image_into(buff_[buffIndex_], net_->w, net_->h, buffLetter_[buffIndex_]); -// return 0; -// } - void* YoloObjectDetector::fetchInThread() { { std::shared_lock lock(mutexImageCallback_); - CvMatWithHeader imageAndHeader = getCvMatWithHeader(); + CvMatWithHeader_ imageAndHeader = getCvMatWithHeader(); free_image(buff_[buffIndex_]); buff_[buffIndex_] = mat_to_image(imageAndHeader.image); headerBuff_[buffIndex_] = imageAndHeader.header; @@ -515,82 +472,24 @@ 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_); -// int c = cv::waitKey(waitKeyDelay_); -// if (c != -1) c = c%256; -// if (c == 27) { -// demoDone_ = 1; -// return 0; -// } else if (c == 82) { -// demoThresh_ += .02; -// } else if (c == 84) { -// demoThresh_ -= .02; -// if(demoThresh_ <= .02) demoThresh_ = .02; -// } else if (c == 83) { -// demoHier_ += .02; -// } else if (c == 81) { -// demoHier_ -= .02; -// if(demoHier_ <= .0) demoHier_ = .0; -// } -// return 0; -// } - void* YoloObjectDetector::displayInThread(void* ptr) { - show_image(buff_[(buffIndex_ + 1) % 3], "YOLO"); - // int c = show_image_cv(buff_[(buffIndex_ + 1) % 3], "YOLO"); - // if (c != -1) c = c % 256; - // if (c == 27) { - // demoDone_ = 1; - // return 0; - // } else if (c == 82) { - // demoThresh_ += .02; - // } else if (c == 84) { - // demoThresh_ -= .02; - // if (demoThresh_ <= .02) demoThresh_ = .02; - // } else if (c == 83) { - // demoHier_ += .02; - // } else if (c == 81) { - // demoHier_ -= .02; - // if (demoHier_ <= .0) demoHier_ = .0; - // } + show_image_cv(buff_[(buffIndex_ + 1) % 3], "YOLO V4"); + int c = cv::waitKey(waitKeyDelay_); + if (c != -1) c = c % 256; + if (c == 27) { + demoDone_ = 1; + return 0; + } else if (c == 82) { + demoThresh_ += .02; + } else if (c == 84) { + demoThresh_ -= .02; + if (demoThresh_ <= .02) demoThresh_ = .02; + } else if (c == 83) { + demoHier_ += .02; + } else if (c == 81) { + demoHier_ -= .02; + if (demoHier_ <= .0) demoHier_ = .0; + } return 0; } @@ -649,32 +548,6 @@ void YoloObjectDetector::setupNetwork(char *cfgfile, char *weightfile, char *dat set_batch_network(net_, 1); } -// void generate_image_cp(image p, IplImage *disp) -> generate_image -// { -// 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() { const auto wait_duration = std::chrono::milliseconds(2000); @@ -702,16 +575,12 @@ void YoloObjectDetector::yolo() layer l = net_->layers[net_->n - 1]; roiBoxes_ = (darknet_ros::RosBox_ *) calloc(l.w * l.h * l.n, sizeof(darknet_ros::RosBox_)); - - std::shared_lock lock(mutexImageCallback_); - // IplImageWithHeader_ imageAndHeader = getIplImageWithHeader(); - // IplImage* ROS_img = imageAndHeader.image; - // buff_[0] = ipl_to_image_cp(ROS_img); - // boost::shared_lock lock(mutexImageCallback_); //for boost - CvMatWithHeader imageAndHeader = getCvMatWithHeader(); - buff_[0] = mat_to_image(imageAndHeader.image); - headerBuff_[0] = imageAndHeader.header; - + { + std::shared_lock lock(mutexImageCallback_); + CvMatWithHeader_ imageAndHeader = getCvMatWithHeader(); + buff_[0] = mat_to_image(imageAndHeader.image); + headerBuff_[0] = imageAndHeader.header; + } buff_[1] = copy_image(buff_[0]); buff_[2] = copy_image(buff_[0]); headerBuff_[1] = headerBuff_[0]; @@ -719,19 +588,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); + // 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("YOLO V4", cv::WINDOW_NORMAL); if (fullScreen_) { - cv::setWindowProperty("YOLO V3", cv::WND_PROP_FULLSCREEN, cv::WINDOW_FULLSCREEN); + cv::setWindowProperty("YOLO V4", cv::WND_PROP_FULLSCREEN, cv::WINDOW_FULLSCREEN); } else { - cv::moveWindow("YOLO V3", 0, 0); - cv::resizeWindow("YOLO V3", 640, 480); + cv::moveWindow("YOLO V4", 0, 0); + cv::resizeWindow("YOLO V4", 640, 480); } } @@ -763,19 +630,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_}; -// return header; -// } - -CvMatWithHeader YoloObjectDetector::getCvMatWithHeader() { - CvMatWithHeader header = {.image = camImageCopy_, .header = imageHeader_}; +CvMatWithHeader_ YoloObjectDetector::getCvMatWithHeader() { + CvMatWithHeader_ header = {.image = camImageCopy_, .header = imageHeader_}; return header; } 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..35f6fb37a --- /dev/null +++ b/darknet_ros/yolo_network_config/cfg/yolov4.cfg @@ -0,0 +1,1160 @@ +[net] +# batch=64 +batch=1 +subdivisions=8 +# 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 \ No newline at end of file From 88cc055b5113041c706e87b4e104c51fad27d7fc Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Sun, 9 May 2021 20:16:50 +0900 Subject: [PATCH 30/64] add YOLOv4.md --- YOLOv4.md | 44 +++++ darknet_ros/config/yolov4.yaml | 168 +++++++++--------- .../darknet_ros/YoloObjectDetector.hpp | 6 +- .../include/darknet_ros/image_interface.hpp | 5 +- darknet_ros/src/YoloObjectDetector.cpp | 6 +- darknet_ros/src/image_interface.cpp | 28 ++- 6 files changed, 147 insertions(+), 110 deletions(-) create mode 100644 YOLOv4.md diff --git a/YOLOv4.md b/YOLOv4.md new file mode 100644 index 000000000..e58f98442 --- /dev/null +++ b/YOLOv4.md @@ -0,0 +1,44 @@ +# Darknet ROS + YOLO v4 + ROS-Foxy + +Writer: [Ar-Ray](https://github.com/Ar-Ray-code) + +## Requirements + +- ROS-Foxy +- CUDA 11.2 +- OpenCV4 + + + +## Installation + +```bash +$ cd +$ mkdir -p ros2_ws/src +$ cd ros2_ws/src +$ git clone --branch foxy-v4 --recursive https://github.com/Ar-Ray-code/darknet_ros.git +$ source /opt/ros/foxy/setup.bash +$ cd ~/ros2_ws +$ colcon build --symlink-install +``` + + + +## Execute YOLO v4 + +Terminal 1 + +```bash +$ source /opt/ros/foxy/setup.bash +$ source ~/ros2_ws/install/local_setup.bash +$ ros2 run v4l2_camera v4l2_camera_node --ros-args -r __ns:=/camera/rgb +``` + +Terminal 2 + +```bash +$ source /opt/ros/foxy/setup.bash +$ source ~/ros2_ws/install/local_setup.bash +$ ros2 run darknet_ros yolov4.launch.py +``` + diff --git a/darknet_ros/config/yolov4.yaml b/darknet_ros/config/yolov4.yaml index 89ed16da5..602a023ee 100644 --- a/darknet_ros/config/yolov4.yaml +++ b/darknet_ros/config/yolov4.yaml @@ -3,89 +3,89 @@ darknet_ros: yolo_model: config_file: name: yolov4.cfg - weight_file: + weight_file: name: yolov4.weights - threshold: + 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 + 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 283a2d45b..d5950126c 100644 --- a/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp +++ b/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp @@ -60,7 +60,7 @@ extern "C" { // #include "demo.h" #include "darknet.h" -#include "darknet_ros/image_interface.hpp" +#include "image_interface.hpp" #include } @@ -269,9 +269,7 @@ class YoloObjectDetector : public rclcpp::Node bool isNodeRunning(void); void *publishInThread(); - - void generate_image(image p, cv::Mat& disp); - + void generate_image_cp(image p, cv::Mat& disp); }; } /* namespace darknet_ros*/ diff --git a/darknet_ros/include/darknet_ros/image_interface.hpp b/darknet_ros/include/darknet_ros/image_interface.hpp index 5bdcd2a8d..80ac09308 100644 --- a/darknet_ros/include/darknet_ros/image_interface.hpp +++ b/darknet_ros/include/darknet_ros/image_interface.hpp @@ -17,7 +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); +void generate_image(image p, cv::Mat& disp); -#endif +#endif \ No newline at end of file diff --git a/darknet_ros/src/YoloObjectDetector.cpp b/darknet_ros/src/YoloObjectDetector.cpp index a1a503f52..87db83dc6 100644 --- a/darknet_ros/src/YoloObjectDetector.cpp +++ b/darknet_ros/src/YoloObjectDetector.cpp @@ -614,8 +614,7 @@ void YoloObjectDetector::yolo() if (viewImage_) { displayInThread(0); } else { - // generate_image_cp(buff_[(buffIndex_ + 1)%3], ipl_); - generate_image(buff_[(buffIndex_ + 1) % 3], disp_); + generate_image_cp(buff_[(buffIndex_ + 1)%3], disp_); } publishInThread(); } else { @@ -726,7 +725,7 @@ void *YoloObjectDetector::publishInThread() return 0; } -void YoloObjectDetector::generate_image(image p, cv::Mat& disp) { +void YoloObjectDetector::generate_image_cp(image p, cv::Mat& disp) { int x, y, k; if (p.c == 3) rgbgr_image(p); // normalize_image(copy); @@ -741,5 +740,4 @@ void YoloObjectDetector::generate_image(image p, cv::Mat& disp) { } } - } /* namespace darknet_ros*/ diff --git a/darknet_ros/src/image_interface.cpp b/darknet_ros/src/image_interface.cpp index 4c7636f90..a59d1875d 100644 --- a/darknet_ros/src/image_interface.cpp +++ b/darknet_ros/src/image_interface.cpp @@ -34,20 +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 From a6cbceedddb26ccaf203a254e025f91ce0655ba9 Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Sun, 9 May 2021 20:55:45 +0900 Subject: [PATCH 31/64] fix confrict 2 --- darknet_ros/CMakeLists.txt | 95 ------------------- darknet_ros/nodelet_plugins.xml | 8 -- .../src/yolo_object_detector_nodelet.cpp | 29 ------ 3 files changed, 132 deletions(-) delete mode 100644 darknet_ros/nodelet_plugins.xml delete mode 100644 darknet_ros/src/yolo_object_detector_nodelet.cpp diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 0163cee09..b94b8070f 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -63,41 +63,16 @@ set(dependencies rclcpp_action std_msgs image_transport -<<<<<<< HEAD cv_bridge sensor_msgs darknet_ros_msgs ament_index_cpp -======= - nodelet ->>>>>>> origin/master ) # Enable OPENCV in darknet # add_definitions(-DOPENCV) add_definitions(-O4 -g) -<<<<<<< HEAD -======= -catkin_package( - INCLUDE_DIRS - include - LIBRARIES - ${PROJECT_NAME}_lib - CATKIN_DEPENDS - cv_bridge - roscpp - actionlib - rospy - std_msgs - darknet_ros_msgs - image_transport - nodelet - DEPENDS - Boost -) - ->>>>>>> origin/master include_directories( ${DARKNET_PATH}/src ${DARKNET_PATH}/include @@ -108,7 +83,6 @@ include_directories( set(PROJECT_LIB_FILES src/YoloObjectDetector.cpp src/image_interface.cpp -<<<<<<< HEAD src/yolo_object_detector_node.cpp ) @@ -152,44 +126,6 @@ set(DARKNET_CORE_FILES ${DARKNET_PATH}/src/yolo_layer.c # ${DARKNET_PATH}/src/yolo_v2_class.cpp # ${DARKNET_PATH}/src/yolo_console_dll.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 ->>>>>>> origin/master ) set(DARKNET_CUDA_FILES @@ -273,25 +209,10 @@ target_link_libraries(${PROJECT_NAME} ) target_compile_definitions(${PROJECT_NAME} PRIVATE -DOPENCV) -<<<<<<< HEAD install(TARGETS ${PROJECT_NAME}_lib ${PROJECT_NAME} ARCHIVE DESTINATION lib LIBRARY DESTINATION lib RUNTIME DESTINATION lib/${PROJECT_NAME} -======= -target_link_libraries(${PROJECT_NAME}_nodelet - ${PROJECT_NAME}_lib -) - -add_dependencies(${PROJECT_NAME}_lib - darknet_ros_msgs_generate_messages_cpp -) - -install(TARGETS ${PROJECT_NAME}_lib - ARCHIVE DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - LIBRARY DESTINATION ${CATKIN_PACKAGE_LIB_DESTINATION} - RUNTIME DESTINATION ${CATKIN_PACKAGE_BIN_DESTINATION} ->>>>>>> origin/master ) @@ -363,7 +284,6 @@ if(BUILD_TESTING) #) endif() -<<<<<<< HEAD ament_export_include_directories(include) ament_export_libraries(${PROJECT_NAME}_lib) @@ -371,18 +291,3 @@ ament_export_libraries(${PROJECT_NAME}_core_lib) ament_export_dependencies(${dependencies}) ament_package() -======= -######################### -### CLANG TOOLING ### -######################### -find_package(cmake_clang_tools QUIET) -if (cmake_clang_tools_FOUND) - message(STATUS "Run clang tooling") - add_clang_tooling( - TARGETS ${PROJECT_NAME} - SOURCE_DIRS ${CMAKE_CURRENT_LIST_DIR}/src ${CMAKE_CURRENT_LIST_DIR}/include ${CMAKE_CURRENT_LIST_DIR}/test - CT_HEADER_DIRS ${CMAKE_CURRENT_LIST_DIR}/include - CF_WERROR - ) -endif (cmake_clang_tools_FOUND) ->>>>>>> origin/master diff --git a/darknet_ros/nodelet_plugins.xml b/darknet_ros/nodelet_plugins.xml deleted file mode 100644 index d5a182fea..000000000 --- a/darknet_ros/nodelet_plugins.xml +++ /dev/null @@ -1,8 +0,0 @@ - - - - - Darknet Ros Nodelet. - - - \ No newline at end of file diff --git a/darknet_ros/src/yolo_object_detector_nodelet.cpp b/darknet_ros/src/yolo_object_detector_nodelet.cpp deleted file mode 100644 index 5e428bfd1..000000000 --- a/darknet_ros/src/yolo_object_detector_nodelet.cpp +++ /dev/null @@ -1,29 +0,0 @@ -/* - * Author: Timon Homberger - * Institute: ETH Zurich, Robotic Systems Lab - */ - -#include -#include -#include -#include - -class DarknetRosNodelet : public nodelet::Nodelet { - public: - DarknetRosNodelet() = default; - ~DarknetRosNodelet() { - if (darknetRos_) delete darknetRos_; - } - - private: - virtual void onInit() { - ros::NodeHandle NodeHandle("~"); - NodeHandle = getPrivateNodeHandle(); - darknetRos_ = new darknet_ros::YoloObjectDetector(NodeHandle); - } - - darknet_ros::YoloObjectDetector* darknetRos_; -}; - -// Declare as a Plug-in -PLUGINLIB_EXPORT_CLASS(DarknetRosNodelet, nodelet::Nodelet); \ No newline at end of file From 98132455f060587b14c3f87678521cf0e61ec52d Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Mon, 10 May 2021 10:01:38 +0900 Subject: [PATCH 32/64] add rm_darknet_CMakeLists --- darknet_ros/CMakeLists.txt | 18 +--- .../darknet_ros/YoloObjectDetector.hpp | 61 +++++++------ .../include/darknet_ros/image_interface.hpp | 1 - darknet_ros/src/YoloObjectDetector.cpp | 88 +++++++++++-------- darknet_ros/src/yolo_object_detector_node.cpp | 2 +- rm_darknet_CMakeLists.sh | 1 + 6 files changed, 91 insertions(+), 80 deletions(-) create mode 100755 rm_darknet_CMakeLists.sh diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index b94b8070f..7e7e2fe58 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -166,10 +166,6 @@ if (CUDA_FOUND) ament_target_dependencies(${PROJECT_NAME} ${dependencies}) - cuda_add_library(${PROJECT_NAME}_nodelet - src/yolo_object_detector_nodelet.cpp - ) - else() add_library(${PROJECT_NAME}_core_lib @@ -187,10 +183,6 @@ else() ) ament_target_dependencies(${PROJECT_NAME} ${dependencies}) - add_library(${PROJECT_NAME}_nodelet - src/yolo_object_detector_nodelet.cpp - ) - endif() target_link_libraries(${PROJECT_NAME}_lib @@ -223,17 +215,13 @@ install( # FILES_MATCHING PATTERN "*.hpp" ) -install(DIRECTORY config launch yolo_network_config - DESTINATION ${CATKIN_PACKAGE_SHARE_DESTINATION} -) - # 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 -q https://github.com/leggedrobotics/darknet_ros/releases/download/1.1.4/yolov2-tiny.weights -P ${PATH}) + execute_process(COMMAND wget http://pjreddie.com/media/files/yolov2-tiny.weights -P ${PATH}) endif() # Download yolov3.weights @@ -241,7 +229,7 @@ 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 -q https://github.com/leggedrobotics/darknet_ros/releases/download/1.1.4/yolov3.weights -P ${PATH}) + execute_process(COMMAND wget http://pjreddie.com/media/files/yolov3.weights -P ${PATH}) endif() install(DIRECTORY yolo_network_config/cfg yolo_network_config/weights DESTINATION share/${PROJECT_NAME}/yolo_network_config/) @@ -266,7 +254,7 @@ if(BUILD_TESTING) 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 -q https://github.com/leggedrobotics/darknet_ros/releases/download/1.1.4/yolov2.weights -P ${PATH}) + execute_process(COMMAND wget http://pjreddie.com/media/files/yolov2.weights -P ${PATH}) endif() find_package(ament_lint_auto REQUIRED) diff --git a/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp b/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp index 534954e0c..d5950126c 100644 --- a/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp +++ b/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp @@ -9,7 +9,12 @@ #pragma once // c++ +#include +#include +#include +#include #include +#include #include #include @@ -22,10 +27,10 @@ #include "image_transport/image_transport.h" // OpenCv -#include -#include #include +#include #include +#include // darknet_ros_msgs #include "darknet_ros_msgs/msg/bounding_boxes.hpp" @@ -35,19 +40,16 @@ // Darknet. #ifdef GPU -#include "cublas_v2.h" #include "cuda_runtime.h" #include "curand.h" +#include "cublas_v2.h" #endif extern "C" { -#include -#include "box.h" -#include "cost_layer.h" -#include "detection_layer.h" #include "network.h" -#include "parser.h" +#include "detection_layer.h" #include "region_layer.h" +#include "cost_layer.h" #include "utils.h" #include "parser.h" #include "box.h" @@ -74,7 +76,8 @@ extern "C" void generate_image(image p, cv::Mat& disp); namespace darknet_ros { //! Bounding box of the detected object. -typedef struct { +typedef struct +{ float x, y, w, h, prob; int num, Class; } RosBox_; @@ -185,8 +188,8 @@ class YoloObjectDetector : public rclcpp::Node std::thread yoloThread_; // Darknet. - char** demoNames_; - image** demoAlphabet_; + char **demoNames_; + image **demoAlphabet_; int demoClasses_; network *net_; @@ -201,24 +204,24 @@ class YoloObjectDetector : public rclcpp::Node float demoThresh_ = 0; float demoHier_ = .5; int running_ = 0; - cv::Mat disp_; + int demoDelay_ = 0; int demoFrame_ = 3; - float** predictions_; + float **predictions_; int demoIndex_ = 0; int demoDone_ = 0; - float* lastAvg2_; - float* lastAvg_; - float* avg_; + float *lastAvg2_; + float *lastAvg_; + float *avg_; int demoTotal_ = 0; double demoTime_; - RosBox_* roiBoxes_; + RosBox_ *roiBoxes_; bool viewImage_; bool enableConsoleOutput_; int waitKeyDelay_; int fullScreen_; - char* demoPrefix_; + char *demoPrefix_; std_msgs::msg::Header imageHeader_; cv::Mat camImageCopy_; @@ -235,24 +238,26 @@ class YoloObjectDetector : public rclcpp::Node // double getWallTime(); - int sizeNetwork(network* net); + int sizeNetwork(network *net); - void rememberNetwork(network* net); + void rememberNetwork(network *net); - detection* avgPredictions(network* net, int* nboxes); + detection *avgPredictions(network *net, int *nboxes); - void* detectInThread(); + void *detectInThread(); - void* fetchInThread(); + void *fetchInThread(); - void* displayInThread(void* ptr); + void *displayInThread(void *ptr); - void* displayLoop(void* ptr); + void *displayLoop(void *ptr); - void* detectLoop(void* ptr); + void *detectLoop(void *ptr); - void setupNetwork(char* cfgfile, char* weightfile, char* datafile, float thresh, char** names, int classes, int delay, char* prefix, - int avg_frames, float hier, int w, int h, int frames, int fullscreen); + void setupNetwork(char *cfgfile, char *weightfile, char *datafile, float thresh, + char **names, int classes, + int delay, char *prefix, int avg_frames, float hier, int w, int h, + int frames, int fullscreen); void yolo(); diff --git a/darknet_ros/include/darknet_ros/image_interface.hpp b/darknet_ros/include/darknet_ros/image_interface.hpp index 844e22ad1..80ac09308 100644 --- a/darknet_ros/include/darknet_ros/image_interface.hpp +++ b/darknet_ros/include/darknet_ros/image_interface.hpp @@ -14,7 +14,6 @@ #include "opencv2/core/version.hpp" #include "image.h" -#include "opencv2/opencv.hpp" static float get_pixel(image m, int x, int y, int c); image **load_alphabet_with_file(char *datafile); diff --git a/darknet_ros/src/YoloObjectDetector.cpp b/darknet_ros/src/YoloObjectDetector.cpp index dc9da5637..87db83dc6 100644 --- a/darknet_ros/src/YoloObjectDetector.cpp +++ b/darknet_ros/src/YoloObjectDetector.cpp @@ -20,10 +20,10 @@ std::string darknetFilePath_ = DARKNET_FILE_PATH; namespace darknet_ros { -char* cfg; -char* weights; -char* data; -char** detectionNames; +char *cfg; +char *weights; +char *data; +char **detectionNames; YoloObjectDetector::YoloObjectDetector() : Node("darknet_ros"), @@ -63,7 +63,8 @@ YoloObjectDetector::YoloObjectDetector() declare_parameter("actions.camera_reading.topic", std::string("check_for_objects")); } -YoloObjectDetector::~YoloObjectDetector() { +YoloObjectDetector::~YoloObjectDetector() +{ { std::unique_lock lockNodeStatus(mutexNodeStatus_); isNodeRunning_ = false; @@ -71,7 +72,8 @@ YoloObjectDetector::~YoloObjectDetector() { yoloThread_.join(); } -bool YoloObjectDetector::readParameters() { +bool YoloObjectDetector::readParameters() +{ // Load common parameters. get_parameter("image_view.enable_opencv", viewImage_); get_parameter("image_view.wait_key_delay", waitKeyDelay_); @@ -137,14 +139,15 @@ void YoloObjectDetector::init() strcpy(data, dataPath.c_str()); // Get classes. - detectionNames = (char**)realloc((void*)detectionNames, (numClasses_ + 1) * sizeof(char*)); + detectionNames = (char**) realloc((void*) detectionNames, (numClasses_ + 1) * sizeof(char*)); for (int i = 0; i < numClasses_; i++) { detectionNames[i] = new char[classLabels_[i].length() + 1]; strcpy(detectionNames[i], classLabels_[i].c_str()); } // Load network. - setupNetwork(cfg, weights, data, thresh, detectionNames, numClasses_, 0, 0, 1, 0.5, 0, 0, 0, 0); + setupNetwork(cfg, weights, data, thresh, detectionNames, numClasses_, + 0, 0, 1, 0.5, 0, 0, 0, 0); yoloThread_ = std::thread(&YoloObjectDetector::yolo, this); // Initialize publisher and subscriber. @@ -322,37 +325,39 @@ int YoloObjectDetector::sizeNetwork(network *net) { int i; int count = 0; - for (i = 0; i < net->n; ++i) { + for(i = 0; i < net->n; ++i){ layer l = net->layers[i]; - if (l.type == YOLO || l.type == REGION || l.type == DETECTION) { + if(l.type == YOLO || l.type == REGION || l.type == DETECTION){ count += l.outputs; } } return count; } -void YoloObjectDetector::rememberNetwork(network* net) { +void YoloObjectDetector::rememberNetwork(network *net) +{ int i; int count = 0; - for (i = 0; i < net->n; ++i) { + for(i = 0; i < net->n; ++i){ layer l = net->layers[i]; - if (l.type == YOLO || l.type == REGION || l.type == DETECTION) { + if(l.type == YOLO || l.type == REGION || l.type == DETECTION){ memcpy(predictions_[demoIndex_] + count, net->layers[i].output, sizeof(float) * l.outputs); count += l.outputs; } } } -detection* YoloObjectDetector::avgPredictions(network* net, int* nboxes) { +detection *YoloObjectDetector::avgPredictions(network *net, int *nboxes) +{ int i, j; int count = 0; fill_cpu(demoTotal_, 0, avg_, 1); - for (j = 0; j < demoFrame_; ++j) { - axpy_cpu(demoTotal_, 1. / demoFrame_, predictions_[j], 1, avg_, 1); + for(j = 0; j < demoFrame_; ++j){ + axpy_cpu(demoTotal_, 1./demoFrame_, predictions_[j], 1, avg_, 1); } - for (i = 0; i < net->n; ++i) { + for(i = 0; i < net->n; ++i){ layer l = net->layers[i]; - if (l.type == YOLO || l.type == REGION || l.type == DETECTION) { + if(l.type == YOLO || l.type == REGION || l.type == DETECTION){ memcpy(l.output, avg_ + count, sizeof(float) * l.outputs); count += l.outputs; } @@ -362,7 +367,8 @@ detection* YoloObjectDetector::avgPredictions(network* net, int* nboxes) { return dets; } -void* YoloObjectDetector::detectInThread() { +void *YoloObjectDetector::detectInThread() +{ running_ = 1; float nms = .4; // mat_cv* show_img = NULL; @@ -372,7 +378,7 @@ void* YoloObjectDetector::detectInThread() { float *prediction = network_predict(*net_, X); rememberNetwork(net_); - detection* dets = 0; + detection *dets = 0; int nboxes = 0; dets = avgPredictions(net_, &nboxes); @@ -381,7 +387,7 @@ void* YoloObjectDetector::detectInThread() { if (enableConsoleOutput_) { printf("\033[2J"); printf("\033[1;1H"); - printf("\nFPS:%.1f\n", fps_); + printf("\nFPS:%.1f\n",fps_); printf("Objects:\n\n"); } image display = buff_[(buffIndex_+2) % 3]; @@ -397,10 +403,14 @@ void* YoloObjectDetector::detectInThread() { float ymin = dets[i].bbox.y - dets[i].bbox.h / 2.; float ymax = dets[i].bbox.y + dets[i].bbox.h / 2.; - if (xmin < 0) xmin = 0; - if (ymin < 0) ymin = 0; - if (xmax > 1) xmax = 1; - if (ymax > 1) ymax = 1; + if (xmin < 0) + xmin = 0; + if (ymin < 0) + ymin = 0; + if (xmax > 1) + xmax = 1; + if (ymax > 1) + ymax = 1; // iterate through possible boxes and collect the bounding boxes for (j = 0; j < demoClasses_; ++j) { @@ -453,6 +463,7 @@ void* YoloObjectDetector::fetchInThread() { return 0; } + float get_pixel_cp(image m, int x, int y, int c) { assert(x < m.w && y < m.h && c < m.c); @@ -465,6 +476,10 @@ void* YoloObjectDetector::displayInThread(void* ptr) { show_image_cv(buff_[(buffIndex_ + 1) % 3], "YOLO V4"); int c = cv::waitKey(waitKeyDelay_); if (c != -1) c = c % 256; + if (c == 27) { + demoDone_ = 1; + return 0; + } else if (c == 82) { demoThresh_ += .02; } else if (c == 84) { demoThresh_ -= .02; @@ -486,7 +501,8 @@ void *YoloObjectDetector::displayLoop(void *ptr) } } -void* YoloObjectDetector::detectLoop(void* ptr) { +void *YoloObjectDetector::detectLoop(void *ptr) +{ while (1) { detectInThread(); } @@ -527,12 +543,13 @@ void YoloObjectDetector::setupNetwork(char *cfgfile, char *weightfile, char *dat demoThresh_ = thresh; demoHier_ = hier; fullScreen_ = fullscreen; - printf("YOLO\n"); + printf("YOLO V3\n"); net_ = load_network(cfgfile, weightfile, 0); set_batch_network(net_, 1); } -void YoloObjectDetector::yolo() { +void YoloObjectDetector::yolo() +{ const auto wait_duration = std::chrono::milliseconds(2000); while (!getImageStatus()) { printf("Waiting for image.\n"); @@ -549,14 +566,14 @@ void YoloObjectDetector::yolo() { int i; demoTotal_ = sizeNetwork(net_); - predictions_ = (float**)calloc(demoFrame_, sizeof(float*)); - for (i = 0; i < demoFrame_; ++i) { - predictions_[i] = (float*)calloc(demoTotal_, sizeof(float)); + predictions_ = (float **) calloc(demoFrame_, sizeof(float*)); + for (i = 0; i < demoFrame_; ++i){ + predictions_[i] = (float *) calloc(demoTotal_, sizeof(float)); } - avg_ = (float*)calloc(demoTotal_, sizeof(float)); + avg_ = (float *) calloc(demoTotal_, sizeof(float)); layer l = net_->layers[net_->n - 1]; - roiBoxes_ = (darknet_ros::RosBox_*)calloc(l.w * l.h * l.n, sizeof(darknet_ros::RosBox_)); + roiBoxes_ = (darknet_ros::RosBox_ *) calloc(l.w * l.h * l.n, sizeof(darknet_ros::RosBox_)); { std::shared_lock lock(mutexImageCallback_); @@ -592,7 +609,7 @@ void YoloObjectDetector::yolo() { fetch_thread = std::thread(&YoloObjectDetector::fetchInThread, this); detect_thread = std::thread(&YoloObjectDetector::detectInThread, this); if (!demoPrefix_) { - fps_ = 1. / (what_time_is_it_now() - demoTime_); + fps_ = 1./(what_time_is_it_now() - demoTime_); demoTime_ = what_time_is_it_now(); if (viewImage_) { displayInThread(0); @@ -631,7 +648,8 @@ bool YoloObjectDetector::isNodeRunning(void) return isNodeRunning_; } -void* YoloObjectDetector::publishInThread() { +void *YoloObjectDetector::publishInThread() +{ // Publish image. // cv::Mat cvImage = cv::cvarrToMat(ipl_); cv::Mat cvImage = disp_; diff --git a/darknet_ros/src/yolo_object_detector_node.cpp b/darknet_ros/src/yolo_object_detector_node.cpp index 1705b88fe..b9bc06793 100644 --- a/darknet_ros/src/yolo_object_detector_node.cpp +++ b/darknet_ros/src/yolo_object_detector_node.cpp @@ -1,5 +1,5 @@ /* - * yolo_object_detector_node.cpp + * yolo_obstacle_detector_node.cpp * * Created on: Dec 19, 2016 * Author: Marko Bjelonic diff --git a/rm_darknet_CMakeLists.sh b/rm_darknet_CMakeLists.sh new file mode 100755 index 000000000..f6cf6dd10 --- /dev/null +++ b/rm_darknet_CMakeLists.sh @@ -0,0 +1 @@ +rm ./darknet/CMakeLists.txt From 76596f762bcd19e3ca878c59bf42fc736778e215 Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Mon, 10 May 2021 10:23:55 +0900 Subject: [PATCH 33/64] update rm_darknet_CMakeLists --- YOLOv4.md | 5 ++--- rm_darknet_CMakeLists.sh | 4 +++- 2 files changed, 5 insertions(+), 4 deletions(-) diff --git a/YOLOv4.md b/YOLOv4.md index e58f98442..de92d1915 100644 --- a/YOLOv4.md +++ b/YOLOv4.md @@ -8,15 +8,14 @@ Writer: [Ar-Ray](https://github.com/Ar-Ray-code) - CUDA 11.2 - OpenCV4 - - ## Installation ```bash $ cd $ mkdir -p ros2_ws/src $ cd ros2_ws/src -$ git clone --branch foxy-v4 --recursive https://github.com/Ar-Ray-code/darknet_ros.git +$ git clone --recursive https://github.com/Ar-Ray-code/darknet_ros.git +$ darknet_ros/rm_darknet_CMakeLists.sh $ source /opt/ros/foxy/setup.bash $ cd ~/ros2_ws $ colcon build --symlink-install diff --git a/rm_darknet_CMakeLists.sh b/rm_darknet_CMakeLists.sh index f6cf6dd10..cda7c8d64 100755 --- a/rm_darknet_CMakeLists.sh +++ b/rm_darknet_CMakeLists.sh @@ -1 +1,3 @@ -rm ./darknet/CMakeLists.txt +#!/bin/sh +SCRIPT_DIR=$(cd $(dirname $0); pwd) +rm $SCRIPT_DIR/darknet/CMakeLists.txt \ No newline at end of file From 00af537f1fc05f6de998272b823ca0967acbb4e9 Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Mon, 10 May 2021 10:30:07 +0900 Subject: [PATCH 34/64] update Link --- README.md | 4 +++- 1 file changed, 3 insertions(+), 1 deletion(-) diff --git a/README.md b/README.md index 9489a9315..47c9dce4e 100644 --- a/README.md +++ b/README.md @@ -1,5 +1,7 @@ # YOLO ROS: Real-Time Object Detection for ROS +Darknet_ros + ROS2 Foxy + YOLO v4 Installation is [here (Jump to Ar-Ray-code/darknet_ros)](https://github.com/Ar-Ray-code/darknet_ros/blob/master/YOLOv4.md). + ## 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/). @@ -179,4 +181,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 `darknet_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 From ae23d0f2fa2fd08b56d61e7aa65c851aa340ae3d Mon Sep 17 00:00:00 2001 From: "Karl D. Hansen" Date: Thu, 20 May 2021 10:48:39 +0200 Subject: [PATCH 35/64] Use encoding reported by camera The camera driver reports its encoding in the sensor_msgs::Image. This string is taken from include/sensor_msgs/image_encodings.h. The most common ones: "mono8" "bgr8" "bgra8" "rgb8" "rgba8" "mono16" are also used for cv_bridge::toCvCopy. So it can be simply passed on. --- darknet_ros/src/YoloObjectDetector.cpp | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/darknet_ros/src/YoloObjectDetector.cpp b/darknet_ros/src/YoloObjectDetector.cpp index 7248a1daf..a38362801 100644 --- a/darknet_ros/src/YoloObjectDetector.cpp +++ b/darknet_ros/src/YoloObjectDetector.cpp @@ -162,7 +162,7 @@ void YoloObjectDetector::cameraCallback(const sensor_msgs::ImageConstPtr& msg) { cv_bridge::CvImagePtr cam_image; try { - cam_image = cv_bridge::toCvCopy(msg, sensor_msgs::image_encodings::BGR8); + cam_image = cv_bridge::toCvCopy(msg, msg->encoding); } catch (cv_bridge::Exception& e) { ROS_ERROR("cv_bridge exception: %s", e.what()); return; From f9c2ad41120041b998ebf190e4f62889a19ea14f Mon Sep 17 00:00:00 2001 From: Tom Lankhorst Date: Fri, 28 May 2021 08:32:28 +0200 Subject: [PATCH 36/64] Update issue templates (#325) --- .github/ISSUE_TEMPLATE/bug_report.md | 33 +++++++++++++++++++ .../compilation-and-runtime-issue.md | 32 ++++++++++++++++++ .github/ISSUE_TEMPLATE/feature_request.md | 20 +++++++++++ 3 files changed, 85 insertions(+) create mode 100644 .github/ISSUE_TEMPLATE/bug_report.md create mode 100644 .github/ISSUE_TEMPLATE/compilation-and-runtime-issue.md create mode 100644 .github/ISSUE_TEMPLATE/feature_request.md diff --git a/.github/ISSUE_TEMPLATE/bug_report.md b/.github/ISSUE_TEMPLATE/bug_report.md new file mode 100644 index 000000000..f5bf685fc --- /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: "[BUG] " +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..fdb9c94ef --- /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: "[QUESTION]" +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..028e6f145 --- /dev/null +++ b/.github/ISSUE_TEMPLATE/feature_request.md @@ -0,0 +1,20 @@ +--- +name: Feature request +about: Suggest an idea for this project +title: "[FEATURE]" +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. From 5b494afe67cbe0b2801a1dabed082501e69f78a0 Mon Sep 17 00:00:00 2001 From: Tom Lankhorst Date: Fri, 28 May 2021 08:35:51 +0200 Subject: [PATCH 37/64] Cutify --- .github/ISSUE_TEMPLATE/bug_report.md | 4 ++-- .github/ISSUE_TEMPLATE/compilation-and-runtime-issue.md | 4 ++-- .github/ISSUE_TEMPLATE/feature_request.md | 4 ++-- 3 files changed, 6 insertions(+), 6 deletions(-) diff --git a/.github/ISSUE_TEMPLATE/bug_report.md b/.github/ISSUE_TEMPLATE/bug_report.md index f5bf685fc..3f205a1c7 100644 --- a/.github/ISSUE_TEMPLATE/bug_report.md +++ b/.github/ISSUE_TEMPLATE/bug_report.md @@ -1,7 +1,7 @@ --- -name: Bug report +name: 🐛 Bug report about: Create a report to help us improve -title: "[BUG] " +title: "[BUG] ..." labels: bug assignees: '' diff --git a/.github/ISSUE_TEMPLATE/compilation-and-runtime-issue.md b/.github/ISSUE_TEMPLATE/compilation-and-runtime-issue.md index fdb9c94ef..1c427ede7 100644 --- a/.github/ISSUE_TEMPLATE/compilation-and-runtime-issue.md +++ b/.github/ISSUE_TEMPLATE/compilation-and-runtime-issue.md @@ -1,7 +1,7 @@ --- -name: Compilation and runtime issue +name: ⁉️ Compilation and runtime issue about: Use this template if you're facing issues running or compiling darknet_ros. -title: "[QUESTION]" +title: "[QUESTION] ..." labels: question assignees: '' diff --git a/.github/ISSUE_TEMPLATE/feature_request.md b/.github/ISSUE_TEMPLATE/feature_request.md index 028e6f145..2bc941a32 100644 --- a/.github/ISSUE_TEMPLATE/feature_request.md +++ b/.github/ISSUE_TEMPLATE/feature_request.md @@ -1,7 +1,7 @@ --- -name: Feature request +name: ✨ Feature request about: Suggest an idea for this project -title: "[FEATURE]" +title: "[FEATURE] ..." labels: enhancement assignees: mbjelonic From e1b9cd279b83de588145f20ec9a94b150651d9ae Mon Sep 17 00:00:00 2001 From: Tom Lankhorst Date: Fri, 28 May 2021 08:37:47 +0200 Subject: [PATCH 38/64] Remove issue title template --- .github/ISSUE_TEMPLATE/bug_report.md | 2 +- .github/ISSUE_TEMPLATE/compilation-and-runtime-issue.md | 2 +- .github/ISSUE_TEMPLATE/feature_request.md | 2 +- 3 files changed, 3 insertions(+), 3 deletions(-) diff --git a/.github/ISSUE_TEMPLATE/bug_report.md b/.github/ISSUE_TEMPLATE/bug_report.md index 3f205a1c7..917ac5cab 100644 --- a/.github/ISSUE_TEMPLATE/bug_report.md +++ b/.github/ISSUE_TEMPLATE/bug_report.md @@ -1,7 +1,7 @@ --- name: 🐛 Bug report about: Create a report to help us improve -title: "[BUG] ..." +title: "" labels: bug assignees: '' diff --git a/.github/ISSUE_TEMPLATE/compilation-and-runtime-issue.md b/.github/ISSUE_TEMPLATE/compilation-and-runtime-issue.md index 1c427ede7..e86674bd6 100644 --- a/.github/ISSUE_TEMPLATE/compilation-and-runtime-issue.md +++ b/.github/ISSUE_TEMPLATE/compilation-and-runtime-issue.md @@ -1,7 +1,7 @@ --- name: ⁉️ Compilation and runtime issue about: Use this template if you're facing issues running or compiling darknet_ros. -title: "[QUESTION] ..." +title: "" labels: question assignees: '' diff --git a/.github/ISSUE_TEMPLATE/feature_request.md b/.github/ISSUE_TEMPLATE/feature_request.md index 2bc941a32..d20dc6d37 100644 --- a/.github/ISSUE_TEMPLATE/feature_request.md +++ b/.github/ISSUE_TEMPLATE/feature_request.md @@ -1,7 +1,7 @@ --- name: ✨ Feature request about: Suggest an idea for this project -title: "[FEATURE] ..." +title: "" labels: enhancement assignees: mbjelonic From 94826f5cc032ba33fbf24ca78a10a995e8366d93 Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Mon, 31 May 2021 18:39:04 +0900 Subject: [PATCH 39/64] add yolov4-csp --- darknet_ros/CMakeLists.txt | 16 +- darknet_ros/config/yolov4-csp.yaml | 91 ++ darknet_ros/launch/darknet_ros_nodelet.launch | 30 - .../launch/darknet_ros_valgrind.launch | 13 - darknet_ros/launch/yolov4-csp.launch.py | 63 + .../yolo_network_config/cfg/yolov4-csp.cfg | 1279 +++++++++++++++++ 6 files changed, 1443 insertions(+), 49 deletions(-) create mode 100644 darknet_ros/config/yolov4-csp.yaml delete mode 100644 darknet_ros/launch/darknet_ros_nodelet.launch delete mode 100644 darknet_ros/launch/darknet_ros_valgrind.launch create mode 100644 darknet_ros/launch/yolov4-csp.launch.py create mode 100644 darknet_ros/yolo_network_config/cfg/yolov4-csp.cfg diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 7e7e2fe58..dfac4c6ae 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -20,12 +20,7 @@ if (CUDA_FOUND) 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_75,code=[sm_75,compute_75] ) add_definitions(-DGPU) else() @@ -243,6 +238,15 @@ if (NOT EXISTS "${FILE}") execute_process(COMMAND wget -q https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v3_optimal/yolov4.weights -P ${PATH}) endif() + +# Download yolov4-csp.weights +set(FILE "${PATH}/yolov4-csp.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_v4_pre/yolov4-csp.weights -P ${PATH}) +endif() + ############# ## Testing ## ############# diff --git a/darknet_ros/config/yolov4-csp.yaml b/darknet_ros/config/yolov4-csp.yaml new file mode 100644 index 000000000..f4b11035b --- /dev/null +++ b/darknet_ros/config/yolov4-csp.yaml @@ -0,0 +1,91 @@ +darknet_ros: + ros__parameters: + yolo_model: + config_file: + name: yolov4-csp.cfg + weight_file: + name: yolov4-csp.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/launch/darknet_ros_nodelet.launch b/darknet_ros/launch/darknet_ros_nodelet.launch deleted file mode 100644 index 357dfc20b..000000000 --- a/darknet_ros/launch/darknet_ros_nodelet.launch +++ /dev/null @@ -1,30 +0,0 @@ - - - - - - - - - - - - - - - - - - - - - - - - - - - - - - \ No newline at end of file diff --git a/darknet_ros/launch/darknet_ros_valgrind.launch b/darknet_ros/launch/darknet_ros_valgrind.launch deleted file mode 100644 index 64f70f583..000000000 --- a/darknet_ros/launch/darknet_ros_valgrind.launch +++ /dev/null @@ -1,13 +0,0 @@ - - - - - - - - - - - - - diff --git a/darknet_ros/launch/yolov4-csp.launch.py b/darknet_ros/launch/yolov4-csp.launch.py new file mode 100644 index 000000000..56ea045ff --- /dev/null +++ b/darknet_ros/launch/yolov4-csp.launch.py @@ -0,0 +1,63 @@ +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, SetEnvironmentVariable +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node + +def generate_launch_description(): + darknet_ros_share_dir = get_package_share_directory('darknet_ros') + + 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/yolov4-csp.yaml') + + declare_image_cmd = DeclareLaunchArgument( + 'image', + 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') + declare_yolo_config_path_cmd = DeclareLaunchArgument( + 'yolo_config_path', + default_value = darknet_ros_share_dir + '/yolo_network_config/cfg', + description = 'Path to yolo config') + declare_ros_param_file_cmd = DeclareLaunchArgument( + 'ros_param_file', + default_value = darknet_ros_share_dir + '/config/ros.yaml', + description = 'Path to file with ROS related config') + declare_network_param_file_cmd = DeclareLaunchArgument( + 'network_param_file', + default_value = darknet_ros_share_dir + '/config/yolov4-csp.yaml', + description = 'Path to file with network param file') + + darknet_ros_cmd = Node( + package='darknet_ros', + node_executable='darknet_ros', + node_name='darknet_ros', + output='screen', + parameters=[ros_param_file, network_param_file, + { + "config_path": yolo_config_path, + "weights_path": yolo_weights_path, + }, + ]) + + ld = LaunchDescription() + + ld.add_action(declare_image_cmd) + ld.add_action(declare_yolo_weights_path_cmd) + ld.add_action(declare_yolo_config_path_cmd) + ld.add_action(declare_ros_param_file_cmd) + ld.add_action(declare_network_param_file_cmd) + + ld.add_action(darknet_ros_cmd) + + return ld 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..f46989fd0 --- /dev/null +++ b/darknet_ros/yolo_network_config/cfg/yolov4-csp.cfg @@ -0,0 +1,1279 @@ +[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 \ No newline at end of file From f4fedfb2ee3d8addb18319dfc676414a4c61bde1 Mon Sep 17 00:00:00 2001 From: Ar-Ray <67567093+Ar-Ray-code@users.noreply.github.com> Date: Tue, 1 Jun 2021 09:02:37 +0900 Subject: [PATCH 40/64] Delete .github/workflows directory --- .github/workflows/catkin-build.yml | 48 ------------------------------ 1 file changed, 48 deletions(-) delete mode 100644 .github/workflows/catkin-build.yml diff --git a/.github/workflows/catkin-build.yml b/.github/workflows/catkin-build.yml deleted file mode 100644 index 6ae7d56a8..000000000 --- a/.github/workflows/catkin-build.yml +++ /dev/null @@ -1,48 +0,0 @@ -name: Build - -on: [push] - -env: - BUILD_TYPE: Release - -jobs: - build: - strategy: - matrix: - container: ["ros:melodic", "ros:noetic"] - runs-on: ubuntu-20.04 - container: ${{ matrix.container }} - - steps: - - name: update git - run: | - apt-get update - apt-get install -y software-properties-common - add-apt-repository ppa:git-core/ppa - apt-get update - apt-get install -y git - - - uses: actions/checkout@v2 - with: - path: src/darknet_ros - submodules: 'recursive' - - - name: rosdep install - run: | - apt-get update - rosdep update - rosdep install --from-paths src --ignore-src -r -y - - - name: catkin_make - shell: bash - run: | - source /opt/ros/$ROS_DISTRO/setup.bash - catkin_make -DCMAKE_BUILD_TYPE=$BUILD_TYPE - - - name: catkin_make run_tests - shell: bash - run: | - source /opt/ros/$ROS_DISTRO/setup.bash - catkin_make run_tests - catkin_test_results - From 22c51eae96fc2d55f2b45de6b68d05ff13dea18e Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Sun, 20 Jun 2021 11:57:45 +0900 Subject: [PATCH 41/64] add cudnn module --- darknet_ros/CMakeLists.txt | 124 ++++++-- darknet_ros/cmake/Modules/FindCUDNN.cmake | 88 ++++++ darknet_ros/config/yolov4-tiny.yaml | 91 ++++++ darknet_ros/launch/yolov2-tiny.launch.py | 63 ++++ darknet_ros/launch/yolov4-tiny.launch.py | 63 ++++ .../yolo_network_config/cfg/yolov4-tiny.cfg | 294 ++++++++++++++++++ 6 files changed, 692 insertions(+), 31 deletions(-) create mode 100644 darknet_ros/cmake/Modules/FindCUDNN.cmake create mode 100644 darknet_ros/config/yolov4-tiny.yaml create mode 100644 darknet_ros/launch/yolov2-tiny.launch.py create mode 100644 darknet_ros/launch/yolov4-tiny.launch.py create mode 100644 darknet_ros/yolo_network_config/cfg/yolov4-tiny.cfg diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index dfac4c6ae..82625f14d 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -1,6 +1,8 @@ cmake_minimum_required(VERSION 3.5) project(darknet_ros) +include(CMakeDependentOption) + set(CMAKE_CXX_STANDARD 17) # Define path of darknet folder here. @@ -20,13 +22,40 @@ if (CUDA_FOUND) CUDA_NVCC_FLAGS ${CUDA_NVCC_FLAGS}; -O3 + -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,compute_61] -gencode arch=compute_75,code=[sm_75,compute_75] ) add_definitions(-DGPU) +endif() + +set(CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/cmake/Modules/" ${CMAKE_MODULE_PATH}) +find_package(CUDNN) + +if(CUDNN_FOUND) + set(ADDITIONAL_CXX_FLAGS "${ADDITIONAL_CXX_FLAGS} -DCUDNN") +endif() + +# ========================================================= +set(CMAKE_CUDA_ARCHITECTURES 75) + +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() +# else() +# list(APPEND LIBRARIES "m") +# endif() + # Find X11 message ( STATUS "Searching for X11..." ) find_package ( X11 REQUIRED ) @@ -82,7 +111,6 @@ set(PROJECT_LIB_FILES ) set(DARKNET_CORE_FILES - ${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 @@ -119,12 +147,9 @@ set(DARKNET_CORE_FILES ${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/yolo_v2_class.cpp - # ${DARKNET_PATH}/src/yolo_console_dll.cpp ) set(DARKNET_CUDA_FILES - ${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 @@ -148,18 +173,48 @@ 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::CuDNN + ) + target_compile_definitions(${PROJECT_NAME}_lib PRIVATE + -DCUDNN + -DCUDNN_HALF + ) + else() + target_link_libraries(${PROJECT_NAME}_lib + cuda + cudart + cublas + curand + cudnn + 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() @@ -207,7 +262,6 @@ install( DIRECTORY include/ DESTINATION include/ FILES_MATCHING PATTERN "*.h" - # FILES_MATCHING PATTERN "*.hpp" ) # Download yolov2-tiny.weights @@ -219,34 +273,42 @@ if (NOT EXISTS "${FILE}") execute_process(COMMAND wget http://pjreddie.com/media/files/yolov2-tiny.weights -P ${PATH}) 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}) -endif() - -install(DIRECTORY yolo_network_config/cfg yolo_network_config/weights DESTINATION share/${PROJECT_NAME}/yolo_network_config/) -install(DIRECTORY launch config DESTINATION share/${PROJECT_NAME}/) +# # 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}) +# 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() +# # 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() # Download yolov4-csp.weights set(FILE "${PATH}/yolov4-csp.weights") -message(STATUS "Checking and downloading yolov4.weights if needed ...") +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() +# Download yolov4-tiny.weights +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 ...") + execute_process(COMMAND wget -q https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v4_pre/yolov4-tiny.weights -P ${PATH}) +endif() + +install(DIRECTORY yolo_network_config/cfg yolo_network_config/weights DESTINATION share/${PROJECT_NAME}/yolo_network_config/) +install(DIRECTORY launch config DESTINATION share/${PROJECT_NAME}/) + ############# ## Testing ## ############# diff --git a/darknet_ros/cmake/Modules/FindCUDNN.cmake b/darknet_ros/cmake/Modules/FindCUDNN.cmake new file mode 100644 index 000000000..871295faa --- /dev/null +++ b/darknet_ros/cmake/Modules/FindCUDNN.cmake @@ -0,0 +1,88 @@ +# Distributed under the OSI-approved BSD 3-Clause License. +# Copyright Stefano Sinigardi + +#.rst: +# FindCUDNN +# -------- +# +# Result Variables +# ^^^^^^^^^^^^^^^^ +# +# This module will set the following variables in your project:: +# +# ``CUDNN_FOUND`` +# True if CUDNN found on the local system +# +# ``CUDNN_INCLUDE_DIRS`` +# Location of CUDNN header files. +# +# ``CUDNN_LIBRARIES`` +# The CUDNN libraries. +# + +include(FindPackageHandleStandardArgs) + +if(NOT CUDNN_INCLUDE_DIR) + find_path(CUDNN_INCLUDE_DIR cudnn.h + HINTS ${CUDA_HOME} ${CUDA_TOOLKIT_ROOT_DIR} $ENV{cudnn} $ENV{CUDNN} + PATH_SUFFIXES cuda/include include) +endif() + +if(NOT CUDNN_LIBRARY) + find_library(CUDNN_LIBRARY cudnn + HINTS ${CUDA_HOME} ${CUDA_TOOLKIT_ROOT_DIR} $ENV{cudnn} $ENV{CUDNN} + PATH_SUFFIXES lib lib64 cuda/lib cuda/lib64 lib/x64) +endif() + +if(EXISTS "${CUDNN_INCLUDE_DIR}/cudnn.h") + file(READ ${CUDNN_INCLUDE_DIR}/cudnn.h CUDNN_HEADER_CONTENTS) + string(REGEX MATCH "define CUDNN_MAJOR * +([0-9]+)" + CUDNN_VERSION_MAJOR "${CUDNN_HEADER_CONTENTS}") + string(REGEX REPLACE "define CUDNN_MAJOR * +([0-9]+)" "\\1" + CUDNN_VERSION_MAJOR "${CUDNN_VERSION_MAJOR}") + string(REGEX MATCH "define CUDNN_MINOR * +([0-9]+)" + CUDNN_VERSION_MINOR "${CUDNN_HEADER_CONTENTS}") + string(REGEX REPLACE "define CUDNN_MINOR * +([0-9]+)" "\\1" + CUDNN_VERSION_MINOR "${CUDNN_VERSION_MINOR}") + string(REGEX MATCH "define CUDNN_PATCHLEVEL * +([0-9]+)" + CUDNN_VERSION_PATCH "${CUDNN_HEADER_CONTENTS}") + string(REGEX REPLACE "define CUDNN_PATCHLEVEL * +([0-9]+)" "\\1" + CUDNN_VERSION_PATCH "${CUDNN_VERSION_PATCH}") + if(NOT CUDNN_VERSION_MAJOR) + set(CUDNN_VERSION "?") + else() + set(CUDNN_VERSION "${CUDNN_VERSION_MAJOR}.${CUDNN_VERSION_MINOR}.${CUDNN_VERSION_PATCH}") + endif() +endif() + +set(CUDNN_INCLUDE_DIRS ${CUDNN_INCLUDE_DIR}) +set(CUDNN_LIBRARIES ${CUDNN_LIBRARY}) +mark_as_advanced(CUDNN_LIBRARY CUDNN_INCLUDE_DIR) + +find_package_handle_standard_args(CUDNN + REQUIRED_VARS CUDNN_INCLUDE_DIR CUDNN_LIBRARY + VERSION_VAR CUDNN_VERSION +) + +if(WIN32) + set(CUDNN_DLL_DIR ${CUDNN_INCLUDE_DIR}) + list(TRANSFORM CUDNN_DLL_DIR APPEND "/../bin") + find_file(CUDNN_LIBRARY_DLL NAMES cudnn64_${CUDNN_VERSION_MAJOR}.dll PATHS ${CUDNN_DLL_DIR}) +endif() + +if( CUDNN_FOUND AND NOT TARGET CuDNN::CuDNN ) + if( EXISTS "${CUDNN_LIBRARY_DLL}" ) + add_library( CuDNN::CuDNN SHARED IMPORTED ) + set_target_properties( CuDNN::CuDNN PROPERTIES + IMPORTED_LOCATION "${CUDNN_LIBRARY_DLL}" + IMPORTED_IMPLIB "${CUDNN_LIBRARY}" + INTERFACE_INCLUDE_DIRECTORIES "${CUDNN_INCLUDE_DIR}" + IMPORTED_LINK_INTERFACE_LANGUAGES "C" ) + else() + add_library( CuDNN::CuDNN UNKNOWN IMPORTED ) + set_target_properties( CuDNN::CuDNN PROPERTIES + IMPORTED_LOCATION "${CUDNN_LIBRARY}" + INTERFACE_INCLUDE_DIRECTORIES "${CUDNN_INCLUDE_DIR}" + IMPORTED_LINK_INTERFACE_LANGUAGES "C" ) + endif() +endif() 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/launch/yolov2-tiny.launch.py b/darknet_ros/launch/yolov2-tiny.launch.py new file mode 100644 index 000000000..4d0c3c08f --- /dev/null +++ b/darknet_ros/launch/yolov2-tiny.launch.py @@ -0,0 +1,63 @@ +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, SetEnvironmentVariable +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node + +def generate_launch_description(): + darknet_ros_share_dir = get_package_share_directory('darknet_ros') + + 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') + + declare_image_cmd = DeclareLaunchArgument( + 'image', + 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') + declare_yolo_config_path_cmd = DeclareLaunchArgument( + 'yolo_config_path', + default_value = darknet_ros_share_dir + '/yolo_network_config/cfg', + description = 'Path to yolo config') + declare_ros_param_file_cmd = DeclareLaunchArgument( + 'ros_param_file', + default_value = darknet_ros_share_dir + '/config/ros.yaml', + 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') + + darknet_ros_cmd = Node( + package='darknet_ros', + node_executable='darknet_ros', + node_name='darknet_ros', + output='screen', + parameters=[ros_param_file, network_param_file, + { + "config_path": yolo_config_path, + "weights_path": yolo_weights_path, + }, + ]) + + ld = LaunchDescription() + + ld.add_action(declare_image_cmd) + ld.add_action(declare_yolo_weights_path_cmd) + ld.add_action(declare_yolo_config_path_cmd) + ld.add_action(declare_ros_param_file_cmd) + ld.add_action(declare_network_param_file_cmd) + + ld.add_action(darknet_ros_cmd) + + return ld diff --git a/darknet_ros/launch/yolov4-tiny.launch.py b/darknet_ros/launch/yolov4-tiny.launch.py new file mode 100644 index 000000000..6eb213889 --- /dev/null +++ b/darknet_ros/launch/yolov4-tiny.launch.py @@ -0,0 +1,63 @@ +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, SetEnvironmentVariable +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node + +def generate_launch_description(): + darknet_ros_share_dir = get_package_share_directory('darknet_ros') + + 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/yolov4-tiny.yaml') + + declare_image_cmd = DeclareLaunchArgument( + 'image', + 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') + declare_yolo_config_path_cmd = DeclareLaunchArgument( + 'yolo_config_path', + default_value = darknet_ros_share_dir + '/yolo_network_config/cfg', + description = 'Path to yolo config') + declare_ros_param_file_cmd = DeclareLaunchArgument( + 'ros_param_file', + default_value = darknet_ros_share_dir + '/config/ros.yaml', + description = 'Path to file with ROS related config') + declare_network_param_file_cmd = DeclareLaunchArgument( + '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', + output='screen', + parameters=[ros_param_file, network_param_file, + { + "config_path": yolo_config_path, + "weights_path": yolo_weights_path, + }, + ]) + + ld = LaunchDescription() + + ld.add_action(declare_image_cmd) + ld.add_action(declare_yolo_weights_path_cmd) + ld.add_action(declare_yolo_config_path_cmd) + ld.add_action(declare_ros_param_file_cmd) + ld.add_action(declare_network_param_file_cmd) + + ld.add_action(darknet_ros_cmd) + + return ld 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..c16b80400 --- /dev/null +++ b/darknet_ros/yolo_network_config/cfg/yolov4-tiny.cfg @@ -0,0 +1,294 @@ +[net] +# Testing +#batch=1 +#subdivisions=1 +# Training +batch=1 +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 \ No newline at end of file From 0b68adc3e295680cbce30ad5e097c5cbe64ab8d2 Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Sun, 20 Jun 2021 12:03:02 +0900 Subject: [PATCH 42/64] rm cmake_modules --- darknet_ros/CMakeLists.txt | 3 +- darknet_ros/cmake/Modules/FindCUDNN.cmake | 88 ----------------------- 2 files changed, 1 insertion(+), 90 deletions(-) delete mode 100644 darknet_ros/cmake/Modules/FindCUDNN.cmake diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 82625f14d..94ab4b894 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -30,14 +30,13 @@ if (CUDA_FOUND) add_definitions(-DGPU) endif() -set(CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/cmake/Modules/" ${CMAKE_MODULE_PATH}) +set(CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/../darknet/cmake/Modules/" ${CMAKE_MODULE_PATH}) find_package(CUDNN) if(CUDNN_FOUND) set(ADDITIONAL_CXX_FLAGS "${ADDITIONAL_CXX_FLAGS} -DCUDNN") endif() -# ========================================================= set(CMAKE_CUDA_ARCHITECTURES 75) if ( 70 IN_LIST CMAKE_CUDA_ARCHITECTURES OR diff --git a/darknet_ros/cmake/Modules/FindCUDNN.cmake b/darknet_ros/cmake/Modules/FindCUDNN.cmake deleted file mode 100644 index 871295faa..000000000 --- a/darknet_ros/cmake/Modules/FindCUDNN.cmake +++ /dev/null @@ -1,88 +0,0 @@ -# Distributed under the OSI-approved BSD 3-Clause License. -# Copyright Stefano Sinigardi - -#.rst: -# FindCUDNN -# -------- -# -# Result Variables -# ^^^^^^^^^^^^^^^^ -# -# This module will set the following variables in your project:: -# -# ``CUDNN_FOUND`` -# True if CUDNN found on the local system -# -# ``CUDNN_INCLUDE_DIRS`` -# Location of CUDNN header files. -# -# ``CUDNN_LIBRARIES`` -# The CUDNN libraries. -# - -include(FindPackageHandleStandardArgs) - -if(NOT CUDNN_INCLUDE_DIR) - find_path(CUDNN_INCLUDE_DIR cudnn.h - HINTS ${CUDA_HOME} ${CUDA_TOOLKIT_ROOT_DIR} $ENV{cudnn} $ENV{CUDNN} - PATH_SUFFIXES cuda/include include) -endif() - -if(NOT CUDNN_LIBRARY) - find_library(CUDNN_LIBRARY cudnn - HINTS ${CUDA_HOME} ${CUDA_TOOLKIT_ROOT_DIR} $ENV{cudnn} $ENV{CUDNN} - PATH_SUFFIXES lib lib64 cuda/lib cuda/lib64 lib/x64) -endif() - -if(EXISTS "${CUDNN_INCLUDE_DIR}/cudnn.h") - file(READ ${CUDNN_INCLUDE_DIR}/cudnn.h CUDNN_HEADER_CONTENTS) - string(REGEX MATCH "define CUDNN_MAJOR * +([0-9]+)" - CUDNN_VERSION_MAJOR "${CUDNN_HEADER_CONTENTS}") - string(REGEX REPLACE "define CUDNN_MAJOR * +([0-9]+)" "\\1" - CUDNN_VERSION_MAJOR "${CUDNN_VERSION_MAJOR}") - string(REGEX MATCH "define CUDNN_MINOR * +([0-9]+)" - CUDNN_VERSION_MINOR "${CUDNN_HEADER_CONTENTS}") - string(REGEX REPLACE "define CUDNN_MINOR * +([0-9]+)" "\\1" - CUDNN_VERSION_MINOR "${CUDNN_VERSION_MINOR}") - string(REGEX MATCH "define CUDNN_PATCHLEVEL * +([0-9]+)" - CUDNN_VERSION_PATCH "${CUDNN_HEADER_CONTENTS}") - string(REGEX REPLACE "define CUDNN_PATCHLEVEL * +([0-9]+)" "\\1" - CUDNN_VERSION_PATCH "${CUDNN_VERSION_PATCH}") - if(NOT CUDNN_VERSION_MAJOR) - set(CUDNN_VERSION "?") - else() - set(CUDNN_VERSION "${CUDNN_VERSION_MAJOR}.${CUDNN_VERSION_MINOR}.${CUDNN_VERSION_PATCH}") - endif() -endif() - -set(CUDNN_INCLUDE_DIRS ${CUDNN_INCLUDE_DIR}) -set(CUDNN_LIBRARIES ${CUDNN_LIBRARY}) -mark_as_advanced(CUDNN_LIBRARY CUDNN_INCLUDE_DIR) - -find_package_handle_standard_args(CUDNN - REQUIRED_VARS CUDNN_INCLUDE_DIR CUDNN_LIBRARY - VERSION_VAR CUDNN_VERSION -) - -if(WIN32) - set(CUDNN_DLL_DIR ${CUDNN_INCLUDE_DIR}) - list(TRANSFORM CUDNN_DLL_DIR APPEND "/../bin") - find_file(CUDNN_LIBRARY_DLL NAMES cudnn64_${CUDNN_VERSION_MAJOR}.dll PATHS ${CUDNN_DLL_DIR}) -endif() - -if( CUDNN_FOUND AND NOT TARGET CuDNN::CuDNN ) - if( EXISTS "${CUDNN_LIBRARY_DLL}" ) - add_library( CuDNN::CuDNN SHARED IMPORTED ) - set_target_properties( CuDNN::CuDNN PROPERTIES - IMPORTED_LOCATION "${CUDNN_LIBRARY_DLL}" - IMPORTED_IMPLIB "${CUDNN_LIBRARY}" - INTERFACE_INCLUDE_DIRECTORIES "${CUDNN_INCLUDE_DIR}" - IMPORTED_LINK_INTERFACE_LANGUAGES "C" ) - else() - add_library( CuDNN::CuDNN UNKNOWN IMPORTED ) - set_target_properties( CuDNN::CuDNN PROPERTIES - IMPORTED_LOCATION "${CUDNN_LIBRARY}" - INTERFACE_INCLUDE_DIRECTORIES "${CUDNN_INCLUDE_DIR}" - IMPORTED_LINK_INTERFACE_LANGUAGES "C" ) - endif() -endif() From 8335e9cbe92abe5c5f42b6048014e45a27ddeec2 Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Sun, 20 Jun 2021 13:06:37 +0900 Subject: [PATCH 43/64] change CMakeLists --- darknet_ros/CMakeLists.txt | 2 -- 1 file changed, 2 deletions(-) diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 94ab4b894..d07f87172 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -179,7 +179,6 @@ if (CUDA_FOUND) cudart cublas curand - cudnn CuDNN::CuDNN ) target_compile_definitions(${PROJECT_NAME}_lib PRIVATE @@ -192,7 +191,6 @@ if (CUDA_FOUND) cudart cublas curand - cudnn CuDNN::CuDNN ) target_compile_definitions(${PROJECT_NAME}_lib PRIVATE From ab48c52ef9620b9be6871af17ba696ab9b908fe0 Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Mon, 21 Jun 2021 18:39:39 +0900 Subject: [PATCH 44/64] change cmakelists --- darknet_ros/CMakeLists.txt | 67 ++++++++++++++++++++++++++------------ 1 file changed, 47 insertions(+), 20 deletions(-) diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index d07f87172..79fd8b3de 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -5,15 +5,27 @@ include(CMakeDependentOption) set(CMAKE_CXX_STANDARD 17) -# Define path of darknet folder here. +# USER SETTINGS ================================================================= + +set(CUDA_ENABLE ON) +set(CUDNN_ENABLE ON) +set(FP16_ENABLE 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) +# Find CUDA ==================================================================== +find_package(CUDA QUIET AND CUDA_ENABLE) if (CUDA_FOUND) find_package(CUDA REQUIRED) message(STATUS "CUDA Version: ${CUDA_VERSION_STRINGS}") @@ -25,19 +37,35 @@ if (CUDA_FOUND) -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,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_86,code=[sm_86,compute_86] # GeForce RTX 3000 Series ) add_definitions(-DGPU) endif() +# Find CUDNN ======================================================================= + set(CMAKE_MODULE_PATH "${CMAKE_CURRENT_LIST_DIR}/../darknet/cmake/Modules/" ${CMAKE_MODULE_PATH}) -find_package(CUDNN) + +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() -set(CMAKE_CUDA_ARCHITECTURES 75) +execute_process ( + COMMAND bash -c "lspci | grep VGA | grep 06:00.0 | 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 @@ -55,7 +83,7 @@ endif() # list(APPEND LIBRARIES "m") # endif() -# Find X11 +# Find X11 ============================================================================ message ( STATUS "Searching for X11..." ) find_package ( X11 REQUIRED ) if ( X11_FOUND ) @@ -197,7 +225,6 @@ if (CUDA_FOUND) -DCUDNN ) endif() - else() target_link_libraries(${PROJECT_NAME}_lib cuda @@ -263,12 +290,12 @@ 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}) -endif() +# 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}) +# endif() # # Download yolov3.weights # set(FILE "${PATH}/yolov3.weights") @@ -286,6 +313,13 @@ endif() # execute_process(COMMAND wget -q https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v3_optimal/yolov4.weights -P ${PATH}) # endif() +# Download yolov4-tiny.weights +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 ...") + execute_process(COMMAND wget -q https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v4_pre/yolov4-tiny.weights -P ${PATH}) +endif() # Download yolov4-csp.weights set(FILE "${PATH}/yolov4-csp.weights") @@ -295,13 +329,6 @@ if (NOT EXISTS "${FILE}") execute_process(COMMAND wget -q https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v4_pre/yolov4-csp.weights -P ${PATH}) endif() -# Download yolov4-tiny.weights -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 ...") - execute_process(COMMAND wget -q https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v4_pre/yolov4-tiny.weights -P ${PATH}) -endif() install(DIRECTORY yolo_network_config/cfg yolo_network_config/weights DESTINATION share/${PROJECT_NAME}/yolo_network_config/) install(DIRECTORY launch config DESTINATION share/${PROJECT_NAME}/) From 68b1e8611d3cfb146f0c6340639a16a429078216 Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Mon, 21 Jun 2021 19:47:50 +0900 Subject: [PATCH 45/64] fix bugs --- darknet_ros/CMakeLists.txt | 32 +++++----- darknet_ros/launch/demo-v4-tiny.launch.py | 72 +++++++++++++++++++++++ darknet_ros/src/YoloObjectDetector.cpp | 2 +- 3 files changed, 90 insertions(+), 16 deletions(-) create mode 100644 darknet_ros/launch/demo-v4-tiny.launch.py diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 79fd8b3de..161e3937e 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -25,9 +25,11 @@ message(STATUS "Darknet path dir = ${DARKNET_PATH}") add_definitions(-DDARKNET_FILE_PATH="${DARKNET_PATH}") # Find CUDA ==================================================================== -find_package(CUDA QUIET AND CUDA_ENABLE) +if(CUDA_ENABLE) + find_package(CUDA) +endif() + if (CUDA_FOUND) - find_package(CUDA REQUIRED) message(STATUS "CUDA Version: ${CUDA_VERSION_STRINGS}") message(STATUS "CUDA Libararies: ${CUDA_LIBRARIES}") set( @@ -337,20 +339,20 @@ 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 @@ -360,7 +362,7 @@ if(BUILD_TESTING) #target_link_libraries(${PROJECT_NAME}_object_detection-test # ${PROJECT_NAME}_lib #) -endif() +# endif() ament_export_include_directories(include) diff --git a/darknet_ros/launch/demo-v4-tiny.launch.py b/darknet_ros/launch/demo-v4-tiny.launch.py new file mode 100644 index 000000000..83f2f9524 --- /dev/null +++ b/darknet_ros/launch/demo-v4-tiny.launch.py @@ -0,0 +1,72 @@ +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, SetEnvironmentVariable +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node + +def generate_launch_description(): + darknet_ros_share_dir = get_package_share_directory('darknet_ros') + + 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/yolov4-tiny.yaml') + + declare_image_cmd = DeclareLaunchArgument( + 'image', + 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') + declare_yolo_config_path_cmd = DeclareLaunchArgument( + 'yolo_config_path', + default_value = darknet_ros_share_dir + '/yolo_network_config/cfg', + description = 'Path to yolo config') + declare_ros_param_file_cmd = DeclareLaunchArgument( + 'ros_param_file', + default_value = darknet_ros_share_dir + '/config/ros.yaml', + description = 'Path to file with ROS related config') + declare_network_param_file_cmd = DeclareLaunchArgument( + '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', + output='screen', + parameters=[ros_param_file, network_param_file, + { + "config_path": yolo_config_path, + "weights_path": yolo_weights_path, + }, + ]) + + camera = Node( + package="v4l2_camera", + executable="v4l2_camera_node", + namespace="camera/rgb", + parameters=[ + {'video_device' : "/dev/video0"}, + ]) + + ld = LaunchDescription() + + ld.add_action(declare_image_cmd) + ld.add_action(declare_yolo_weights_path_cmd) + ld.add_action(declare_yolo_config_path_cmd) + ld.add_action(declare_ros_param_file_cmd) + ld.add_action(declare_network_param_file_cmd) + + ld.add_action(darknet_ros_cmd) + ld.add_action(camera) + + return ld diff --git a/darknet_ros/src/YoloObjectDetector.cpp b/darknet_ros/src/YoloObjectDetector.cpp index d7e3f3dc9..87db83dc6 100644 --- a/darknet_ros/src/YoloObjectDetector.cpp +++ b/darknet_ros/src/YoloObjectDetector.cpp @@ -225,7 +225,7 @@ void YoloObjectDetector::cameraCallback(const sensor_msgs::msg::Image::ConstShar cv_bridge::CvImagePtr cam_image; try { - cam_image = cv_bridge::toCvCopy(msg, msg->encoding); + cam_image = cv_bridge::toCvCopy(msg, "bgr8"); } catch (cv_bridge::Exception& e) { RCLCPP_ERROR(get_logger(), "cv_bridge exception: %s", e.what()); return; From c76774b5b43322fd2bdff81a7ff746a75b3b3064 Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Sat, 26 Jun 2021 21:40:59 +0900 Subject: [PATCH 46/64] for benchmark --- darknet_ros/CMakeLists.txt | 2 +- darknet_ros/config/yolov4x-mish.yaml | 91 ++ .../darknet_ros/YoloObjectDetector.hpp | 8 + darknet_ros/launch/demo-v4-csp.launch.py | 72 + darknet_ros/launch/demo-v4-tiny.launch.py | 4 +- darknet_ros/launch/demo-v4.launch.py | 72 + darknet_ros/launch/demo-v4x-mish.launch.py | 72 + darknet_ros/src/YoloObjectDetector.cpp | 16 +- .../yolo_network_config/cfg/yolov4-tiny.cfg | 2 +- .../yolo_network_config/cfg/yolov4.cfg | 4 +- .../yolo_network_config/cfg/yolov4x-mish.cfg | 1436 +++++++++++++++++ 11 files changed, 1772 insertions(+), 7 deletions(-) create mode 100644 darknet_ros/config/yolov4x-mish.yaml create mode 100644 darknet_ros/launch/demo-v4-csp.launch.py create mode 100644 darknet_ros/launch/demo-v4.launch.py create mode 100644 darknet_ros/launch/demo-v4x-mish.launch.py create mode 100644 darknet_ros/yolo_network_config/cfg/yolov4x-mish.cfg diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 161e3937e..1c5718d7d 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -61,7 +61,7 @@ if(CUDNN_FOUND) endif() execute_process ( - COMMAND bash -c "lspci | grep VGA | grep 06:00.0 | grep -e TU106 -e TU104 -e TU102 -e GA106 -e GA104 -e GA102" + 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} ) diff --git a/darknet_ros/config/yolov4x-mish.yaml b/darknet_ros/config/yolov4x-mish.yaml new file mode 100644 index 000000000..d22686d7a --- /dev/null +++ b/darknet_ros/config/yolov4x-mish.yaml @@ -0,0 +1,91 @@ +darknet_ros: + ros__parameters: + yolo_model: + config_file: + name: yolov4x-mish.cfg + weight_file: + name: yolov4x-mish.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 d5950126c..4cb458845 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" @@ -62,6 +65,8 @@ extern "C" { #include "image_interface.hpp" +#define START_COUNT 100 + #include } @@ -201,6 +206,9 @@ class YoloObjectDetector : public rclcpp::Node // 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; diff --git a/darknet_ros/launch/demo-v4-csp.launch.py b/darknet_ros/launch/demo-v4-csp.launch.py new file mode 100644 index 000000000..35950ad84 --- /dev/null +++ b/darknet_ros/launch/demo-v4-csp.launch.py @@ -0,0 +1,72 @@ +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, SetEnvironmentVariable +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node + +def generate_launch_description(): + darknet_ros_share_dir = get_package_share_directory('darknet_ros') + + 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/yolov4-csp.yaml') + + declare_image_cmd = DeclareLaunchArgument( + 'image', + 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') + declare_yolo_config_path_cmd = DeclareLaunchArgument( + 'yolo_config_path', + default_value = darknet_ros_share_dir + '/yolo_network_config/cfg', + description = 'Path to yolo config') + declare_ros_param_file_cmd = DeclareLaunchArgument( + 'ros_param_file', + default_value = darknet_ros_share_dir + '/config/ros.yaml', + description = 'Path to file with ROS related config') + declare_network_param_file_cmd = DeclareLaunchArgument( + 'network_param_file', + default_value = darknet_ros_share_dir + '/config/yolov4-csp.yaml', + description = 'Path to file with network param file') + + darknet_ros_cmd = Node( + package='darknet_ros', + node_executable='darknet_ros', + node_name='darknet_ros', + output='screen', + parameters=[ros_param_file, network_param_file, + { + "config_path": yolo_config_path, + "weights_path": yolo_weights_path, + }, + ]) + + camera = Node( + package="v4l2_camera", + node_executable="v4l2_camera_node", + node_namespace="camera/rgb", + parameters=[ + {'video_device' : "/dev/video0"}, + ]) + + ld = LaunchDescription() + + ld.add_action(declare_image_cmd) + ld.add_action(declare_yolo_weights_path_cmd) + ld.add_action(declare_yolo_config_path_cmd) + ld.add_action(declare_ros_param_file_cmd) + ld.add_action(declare_network_param_file_cmd) + + ld.add_action(darknet_ros_cmd) + ld.add_action(camera) + + return ld diff --git a/darknet_ros/launch/demo-v4-tiny.launch.py b/darknet_ros/launch/demo-v4-tiny.launch.py index 83f2f9524..a217b94b4 100644 --- a/darknet_ros/launch/demo-v4-tiny.launch.py +++ b/darknet_ros/launch/demo-v4-tiny.launch.py @@ -52,8 +52,8 @@ def generate_launch_description(): camera = Node( package="v4l2_camera", - executable="v4l2_camera_node", - namespace="camera/rgb", + node_executable="v4l2_camera_node", + node_namespace="camera/rgb", parameters=[ {'video_device' : "/dev/video0"}, ]) diff --git a/darknet_ros/launch/demo-v4.launch.py b/darknet_ros/launch/demo-v4.launch.py new file mode 100644 index 000000000..c5db48833 --- /dev/null +++ b/darknet_ros/launch/demo-v4.launch.py @@ -0,0 +1,72 @@ +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, SetEnvironmentVariable +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node + +def generate_launch_description(): + darknet_ros_share_dir = get_package_share_directory('darknet_ros') + + 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/yolov4.yaml') + + declare_image_cmd = DeclareLaunchArgument( + 'image', + 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') + declare_yolo_config_path_cmd = DeclareLaunchArgument( + 'yolo_config_path', + default_value = darknet_ros_share_dir + '/yolo_network_config/cfg', + description = 'Path to yolo config') + declare_ros_param_file_cmd = DeclareLaunchArgument( + 'ros_param_file', + default_value = darknet_ros_share_dir + '/config/ros.yaml', + description = 'Path to file with ROS related config') + declare_network_param_file_cmd = DeclareLaunchArgument( + 'network_param_file', + default_value = darknet_ros_share_dir + '/config/yolov4.yaml', + description = 'Path to file with network param file') + + darknet_ros_cmd = Node( + package='darknet_ros', + node_executable='darknet_ros', + node_name='darknet_ros', + output='screen', + parameters=[ros_param_file, network_param_file, + { + "config_path": yolo_config_path, + "weights_path": yolo_weights_path, + }, + ]) + + camera = Node( + package="v4l2_camera", + node_executable="v4l2_camera_node", + node_namespace="camera/rgb", + parameters=[ + {'video_device' : "/dev/video0"}, + ]) + + ld = LaunchDescription() + + ld.add_action(declare_image_cmd) + ld.add_action(declare_yolo_weights_path_cmd) + ld.add_action(declare_yolo_config_path_cmd) + ld.add_action(declare_ros_param_file_cmd) + ld.add_action(declare_network_param_file_cmd) + + ld.add_action(darknet_ros_cmd) + ld.add_action(camera) + + return ld diff --git a/darknet_ros/launch/demo-v4x-mish.launch.py b/darknet_ros/launch/demo-v4x-mish.launch.py new file mode 100644 index 000000000..78a3c371c --- /dev/null +++ b/darknet_ros/launch/demo-v4x-mish.launch.py @@ -0,0 +1,72 @@ +import os + +from ament_index_python.packages import get_package_share_directory + +from launch import LaunchDescription +from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, SetEnvironmentVariable +from launch.launch_description_sources import PythonLaunchDescriptionSource +from launch.substitutions import LaunchConfiguration +from launch_ros.actions import Node + +def generate_launch_description(): + darknet_ros_share_dir = get_package_share_directory('darknet_ros') + + 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/yolov4x-mish.yaml') + + declare_image_cmd = DeclareLaunchArgument( + 'image', + 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') + declare_yolo_config_path_cmd = DeclareLaunchArgument( + 'yolo_config_path', + default_value = darknet_ros_share_dir + '/yolo_network_config/cfg', + description = 'Path to yolo config') + declare_ros_param_file_cmd = DeclareLaunchArgument( + 'ros_param_file', + default_value = darknet_ros_share_dir + '/config/ros.yaml', + description = 'Path to file with ROS related config') + declare_network_param_file_cmd = DeclareLaunchArgument( + 'network_param_file', + default_value = darknet_ros_share_dir + '/config/yolov4x-mish.yaml', + description = 'Path to file with network param file') + + darknet_ros_cmd = Node( + package='darknet_ros', + node_executable='darknet_ros', + node_name='darknet_ros', + output='screen', + parameters=[ros_param_file, network_param_file, + { + "config_path": yolo_config_path, + "weights_path": yolo_weights_path, + }, + ]) + + camera = Node( + package="v4l2_camera", + node_executable="v4l2_camera_node", + node_namespace="camera/rgb", + parameters=[ + {'video_device' : "/dev/video0"}, + ]) + + ld = LaunchDescription() + + ld.add_action(declare_image_cmd) + ld.add_action(declare_yolo_weights_path_cmd) + ld.add_action(declare_yolo_config_path_cmd) + ld.add_action(declare_ros_param_file_cmd) + ld.add_action(declare_network_param_file_cmd) + + ld.add_action(darknet_ros_cmd) + ld.add_action(camera) + + return ld diff --git a/darknet_ros/src/YoloObjectDetector.cpp b/darknet_ros/src/YoloObjectDetector.cpp index 87db83dc6..7bec08e0a 100644 --- a/darknet_ros/src/YoloObjectDetector.cpp +++ b/darknet_ros/src/YoloObjectDetector.cpp @@ -387,7 +387,7 @@ 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]; @@ -550,6 +550,7 @@ void YoloObjectDetector::setupNetwork(char *cfgfile, char *weightfile, char *dat void YoloObjectDetector::yolo() { + static int start_count = 0; const auto wait_duration = std::chrono::milliseconds(2000); while (!getImageStatus()) { printf("Waiting for image.\n"); @@ -610,6 +611,19 @@ 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); diff --git a/darknet_ros/yolo_network_config/cfg/yolov4-tiny.cfg b/darknet_ros/yolo_network_config/cfg/yolov4-tiny.cfg index c16b80400..503f9334d 100644 --- a/darknet_ros/yolo_network_config/cfg/yolov4-tiny.cfg +++ b/darknet_ros/yolo_network_config/cfg/yolov4-tiny.cfg @@ -291,4 +291,4 @@ resize=1.5 nms_kind=greedynms beta_nms=0.6 #new_coords=1 -#scale_x_y = 2.0 \ No newline at end of file +#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 index 35f6fb37a..df1cbd523 100644 --- a/darknet_ros/yolo_network_config/cfg/yolov4.cfg +++ b/darknet_ros/yolo_network_config/cfg/yolov4.cfg @@ -1,7 +1,7 @@ [net] # batch=64 batch=1 -subdivisions=8 +subdivisions=1 # Training #width=512 #height=512 @@ -1157,4 +1157,4 @@ iou_normalizer=0.07 iou_loss=ciou nms_kind=greedynms beta_nms=0.6 -max_delta=5 \ No newline at end of file +max_delta=5 diff --git a/darknet_ros/yolo_network_config/cfg/yolov4x-mish.cfg b/darknet_ros/yolo_network_config/cfg/yolov4x-mish.cfg new file mode 100644 index 000000000..ab598f6e7 --- /dev/null +++ b/darknet_ros/yolo_network_config/cfg/yolov4x-mish.cfg @@ -0,0 +1,1436 @@ +[net] +# Testing +#batch=1 +#subdivisions=1 +# Training +batch=1 +subdivisions=1 +width=640 +height=640 +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 + +#optimized_memory=1 + +[convolutional] +batch_normalize=1 +filters=32 +size=3 +stride=1 +pad=1 +activation=mish + +# Downsample + +[convolutional] +batch_normalize=1 +filters=80 +size=3 +stride=2 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=40 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=80 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +# Downsample + +[convolutional] +batch_normalize=1 +filters=160 +size=3 +stride=2 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=80 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=80 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=80 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=80 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=80 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=80 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=80 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=80 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=80 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -1,-13 + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +# Downsample + +[convolutional] +batch_normalize=1 +filters=320 +size=3 +stride=2 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=160 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=160 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=160 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=160 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=160 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=160 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=160 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=160 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=160 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=160 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -1,-34 + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +# Downsample + +[convolutional] +batch_normalize=1 +filters=640 +size=3 +stride=2 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=320 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=320 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=320 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=320 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=320 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=320 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=320 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=320 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=320 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=320 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -1,-34 + +[convolutional] +batch_normalize=1 +filters=640 +size=1 +stride=1 +pad=1 +activation=mish + +# Downsample + +[convolutional] +batch_normalize=1 +filters=1280 +size=3 +stride=2 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=640 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=640 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=640 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=640 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=640 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=640 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=640 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=640 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=640 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=640 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=640 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=640 +size=3 +stride=1 +pad=1 +activation=mish + +[shortcut] +from=-3 +activation=linear + +[convolutional] +batch_normalize=1 +filters=640 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -1,-19 + +[convolutional] +batch_normalize=1 +filters=1280 +size=1 +stride=1 +pad=1 +activation=mish + +########################## 6 0 6 6 3 + +[convolutional] +batch_normalize=1 +filters=640 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=640 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=640 +activation=mish + +[convolutional] +batch_normalize=1 +filters=640 +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=640 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=640 +activation=mish + +[convolutional] +batch_normalize=1 +filters=640 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=640 +activation=mish + +[route] +layers = -1, -15 + +[convolutional] +batch_normalize=1 +filters=640 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[upsample] +stride=2 + +[route] +layers = 94 + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -1, -3 + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=320 +activation=mish + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=320 +activation=mish + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=320 +activation=mish + +[route] +layers = -1, -8 + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +[upsample] +stride=2 + +[route] +layers = 57 + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -1, -3 + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=160 +activation=mish + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=160 +activation=mish + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=160 +activation=mish + +[route] +layers = -1, -8 + +[convolutional] +batch_normalize=1 +filters=160 +size=1 +stride=1 +pad=1 +activation=mish +stopbackward=800 + +########################## + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=320 +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=320 +activation=mish + +[route] +layers = -1, -22 + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=320 +activation=mish + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=320 +activation=mish + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=320 +activation=mish + +[route] +layers = -1,-8 + +[convolutional] +batch_normalize=1 +filters=320 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=640 +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=640 +activation=mish + +[route] +layers = -1, -55 + +[convolutional] +batch_normalize=1 +filters=640 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +filters=640 +size=1 +stride=1 +pad=1 +activation=mish + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=640 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=640 +activation=mish + +[convolutional] +batch_normalize=1 +filters=640 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=640 +activation=mish + +[convolutional] +batch_normalize=1 +filters=640 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=640 +activation=mish + +[route] +layers = -1,-8 + +[convolutional] +batch_normalize=1 +filters=640 +size=1 +stride=1 +pad=1 +activation=mish + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=1280 +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 From bb77da8d7c1e361e9c2612033d31fe5464e245d5 Mon Sep 17 00:00:00 2001 From: Ar-Ray <67567093+Ar-Ray-code@users.noreply.github.com> Date: Sun, 27 Jun 2021 15:20:35 +0900 Subject: [PATCH 47/64] CUDA REQUIRED Currently it is not possible to compile for CPU-only inference ... --- darknet_ros/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 1c5718d7d..30329fec3 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -26,7 +26,7 @@ add_definitions(-DDARKNET_FILE_PATH="${DARKNET_PATH}") # Find CUDA ==================================================================== if(CUDA_ENABLE) - find_package(CUDA) + find_package(CUDA REQUIRED) endif() if (CUDA_FOUND) From 5de05facd17731462b7c177c9c9aaa299deb715d Mon Sep 17 00:00:00 2001 From: Ar-Ray <67567093+Ar-Ray-code@users.noreply.github.com> Date: Sun, 27 Jun 2021 15:20:35 +0900 Subject: [PATCH 48/64] CUDA REQUIRED Currently it is not possible to compile for CPU-only inference ... --- darknet_ros/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 1c5718d7d..30329fec3 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -26,7 +26,7 @@ add_definitions(-DDARKNET_FILE_PATH="${DARKNET_PATH}") # Find CUDA ==================================================================== if(CUDA_ENABLE) - find_package(CUDA) + find_package(CUDA REQUIRED) endif() if (CUDA_FOUND) From 6e04200d347a695ab17f9d2b19c967c63d09f7b0 Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Thu, 12 Aug 2021 16:11:50 +0900 Subject: [PATCH 49/64] launch concisely --- darknet_ros/CMakeLists.txt | 2 +- darknet_ros/config/ros.yaml | 2 +- darknet_ros/launch/darknet_ros.launch.py | 12 ++-- darknet_ros/launch/demo-v4-csp.launch.py | 63 ++++---------------- darknet_ros/launch/demo-v4-tiny.launch.py | 63 ++++---------------- darknet_ros/launch/demo-v4.launch.py | 63 ++++---------------- darknet_ros/launch/demo-v4x-mish.launch.py | 63 ++++---------------- darknet_ros/launch/yolov2-tiny.launch.py | 68 ++++++---------------- darknet_ros/launch/yolov4-csp.launch.py | 68 ++++++---------------- darknet_ros/launch/yolov4-tiny.launch.py | 68 ++++++---------------- darknet_ros/launch/yolov4.launch.py | 68 ++++++---------------- 11 files changed, 132 insertions(+), 408 deletions(-) diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 30329fec3..4f6540d50 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -8,7 +8,7 @@ set(CMAKE_CXX_STANDARD 17) # USER SETTINGS ================================================================= set(CUDA_ENABLE ON) -set(CUDNN_ENABLE ON) +set(CUDNN_ENABLE OFF) # set(CUDNN_ENABLE ON) set(FP16_ENABLE ON) # Jetson AGX Xavier & TITAN V is under version of Turing. So, please set manually. 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/launch/darknet_ros.launch.py b/darknet_ros/launch/darknet_ros.launch.py index 689c1a9fe..8d00fe302 100644 --- a/darknet_ros/launch/darknet_ros.launch.py +++ b/darknet_ros/launch/darknet_ros.launch.py @@ -15,16 +15,16 @@ def generate_launch_description(): 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/yolov3.yaml') + network_param_file = LaunchConfiguration('network_param_file', default = darknet_ros_share_dir + 'config/yolov2-tiny.yaml') declare_image_cmd = DeclareLaunchArgument( 'image', - default_value = '/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,8 +35,8 @@ 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/yolov3.yaml', - description = 'Path to file with network param file') + default_value = darknet_ros_share_dir + '/config/yolov2-tiny.yaml', + description = 'Path to file with network param file') darknet_ros_cmd = Node( package='darknet_ros', @@ -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/demo-v4-csp.launch.py b/darknet_ros/launch/demo-v4-csp.launch.py index 35950ad84..6ddcb4371 100644 --- a/darknet_ros/launch/demo-v4-csp.launch.py +++ b/darknet_ros/launch/demo-v4-csp.launch.py @@ -10,63 +10,24 @@ 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' - 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/yolov4-csp.yaml') - - declare_image_cmd = DeclareLaunchArgument( - 'image', - 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') - declare_yolo_config_path_cmd = DeclareLaunchArgument( - 'yolo_config_path', - default_value = darknet_ros_share_dir + '/yolo_network_config/cfg', - description = 'Path to yolo config') - declare_ros_param_file_cmd = DeclareLaunchArgument( - 'ros_param_file', - default_value = darknet_ros_share_dir + '/config/ros.yaml', - description = 'Path to file with ROS related config') - declare_network_param_file_cmd = DeclareLaunchArgument( - 'network_param_file', - default_value = darknet_ros_share_dir + '/config/yolov4-csp.yaml', - description = 'Path to file with network param file') - - darknet_ros_cmd = Node( - package='darknet_ros', - node_executable='darknet_ros', - node_name='darknet_ros', - output='screen', - parameters=[ros_param_file, network_param_file, - { - "config_path": yolo_config_path, - "weights_path": yolo_weights_path, - }, - ]) + 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", node_executable="v4l2_camera_node", - node_namespace="camera/rgb", + # node_namespace="camera/rgb", parameters=[ {'video_device' : "/dev/video0"}, ]) - - ld = LaunchDescription() - - ld.add_action(declare_image_cmd) - ld.add_action(declare_yolo_weights_path_cmd) - ld.add_action(declare_yolo_config_path_cmd) - ld.add_action(declare_ros_param_file_cmd) - ld.add_action(declare_network_param_file_cmd) - ld.add_action(darknet_ros_cmd) - ld.add_action(camera) - - return ld + return LaunchDescription([ + darknet_ros_launch, + camera, + ]) \ No newline at end of file diff --git a/darknet_ros/launch/demo-v4-tiny.launch.py b/darknet_ros/launch/demo-v4-tiny.launch.py index a217b94b4..235d06db5 100644 --- a/darknet_ros/launch/demo-v4-tiny.launch.py +++ b/darknet_ros/launch/demo-v4-tiny.launch.py @@ -10,63 +10,24 @@ 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' - 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/yolov4-tiny.yaml') - - declare_image_cmd = DeclareLaunchArgument( - 'image', - 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') - declare_yolo_config_path_cmd = DeclareLaunchArgument( - 'yolo_config_path', - default_value = darknet_ros_share_dir + '/yolo_network_config/cfg', - description = 'Path to yolo config') - declare_ros_param_file_cmd = DeclareLaunchArgument( - 'ros_param_file', - default_value = darknet_ros_share_dir + '/config/ros.yaml', - description = 'Path to file with ROS related config') - declare_network_param_file_cmd = DeclareLaunchArgument( - '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', - output='screen', - parameters=[ros_param_file, network_param_file, - { - "config_path": yolo_config_path, - "weights_path": yolo_weights_path, - }, - ]) + 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", node_executable="v4l2_camera_node", - node_namespace="camera/rgb", + # node_namespace="camera/rgb", parameters=[ {'video_device' : "/dev/video0"}, ]) - - ld = LaunchDescription() - - ld.add_action(declare_image_cmd) - ld.add_action(declare_yolo_weights_path_cmd) - ld.add_action(declare_yolo_config_path_cmd) - ld.add_action(declare_ros_param_file_cmd) - ld.add_action(declare_network_param_file_cmd) - ld.add_action(darknet_ros_cmd) - ld.add_action(camera) - - return ld + return LaunchDescription([ + darknet_ros_launch, + camera, + ]) \ No newline at end of file diff --git a/darknet_ros/launch/demo-v4.launch.py b/darknet_ros/launch/demo-v4.launch.py index c5db48833..61e3cd808 100644 --- a/darknet_ros/launch/demo-v4.launch.py +++ b/darknet_ros/launch/demo-v4.launch.py @@ -10,63 +10,24 @@ def generate_launch_description(): darknet_ros_share_dir = get_package_share_directory('darknet_ros') + network_param_file = darknet_ros_share_dir + '/config/yolov4.yaml' - 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/yolov4.yaml') - - declare_image_cmd = DeclareLaunchArgument( - 'image', - 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') - declare_yolo_config_path_cmd = DeclareLaunchArgument( - 'yolo_config_path', - default_value = darknet_ros_share_dir + '/yolo_network_config/cfg', - description = 'Path to yolo config') - declare_ros_param_file_cmd = DeclareLaunchArgument( - 'ros_param_file', - default_value = darknet_ros_share_dir + '/config/ros.yaml', - description = 'Path to file with ROS related config') - declare_network_param_file_cmd = DeclareLaunchArgument( - 'network_param_file', - default_value = darknet_ros_share_dir + '/config/yolov4.yaml', - description = 'Path to file with network param file') - - darknet_ros_cmd = Node( - package='darknet_ros', - node_executable='darknet_ros', - node_name='darknet_ros', - output='screen', - parameters=[ros_param_file, network_param_file, - { - "config_path": yolo_config_path, - "weights_path": yolo_weights_path, - }, - ]) + 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", node_executable="v4l2_camera_node", - node_namespace="camera/rgb", + # node_namespace="camera/rgb", parameters=[ {'video_device' : "/dev/video0"}, ]) - - ld = LaunchDescription() - - ld.add_action(declare_image_cmd) - ld.add_action(declare_yolo_weights_path_cmd) - ld.add_action(declare_yolo_config_path_cmd) - ld.add_action(declare_ros_param_file_cmd) - ld.add_action(declare_network_param_file_cmd) - ld.add_action(darknet_ros_cmd) - ld.add_action(camera) - - return ld + return LaunchDescription([ + darknet_ros_launch, + camera, + ]) \ No newline at end of file diff --git a/darknet_ros/launch/demo-v4x-mish.launch.py b/darknet_ros/launch/demo-v4x-mish.launch.py index 78a3c371c..ceccfce33 100644 --- a/darknet_ros/launch/demo-v4x-mish.launch.py +++ b/darknet_ros/launch/demo-v4x-mish.launch.py @@ -10,63 +10,24 @@ def generate_launch_description(): darknet_ros_share_dir = get_package_share_directory('darknet_ros') + network_param_file = darknet_ros_share_dir + '/config/yolov4-mish.yaml' - 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/yolov4x-mish.yaml') - - declare_image_cmd = DeclareLaunchArgument( - 'image', - 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') - declare_yolo_config_path_cmd = DeclareLaunchArgument( - 'yolo_config_path', - default_value = darknet_ros_share_dir + '/yolo_network_config/cfg', - description = 'Path to yolo config') - declare_ros_param_file_cmd = DeclareLaunchArgument( - 'ros_param_file', - default_value = darknet_ros_share_dir + '/config/ros.yaml', - description = 'Path to file with ROS related config') - declare_network_param_file_cmd = DeclareLaunchArgument( - 'network_param_file', - default_value = darknet_ros_share_dir + '/config/yolov4x-mish.yaml', - description = 'Path to file with network param file') - - darknet_ros_cmd = Node( - package='darknet_ros', - node_executable='darknet_ros', - node_name='darknet_ros', - output='screen', - parameters=[ros_param_file, network_param_file, - { - "config_path": yolo_config_path, - "weights_path": yolo_weights_path, - }, - ]) + 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", node_executable="v4l2_camera_node", - node_namespace="camera/rgb", + # node_namespace="camera/rgb", parameters=[ {'video_device' : "/dev/video0"}, ]) - - ld = LaunchDescription() - - ld.add_action(declare_image_cmd) - ld.add_action(declare_yolo_weights_path_cmd) - ld.add_action(declare_yolo_config_path_cmd) - ld.add_action(declare_ros_param_file_cmd) - ld.add_action(declare_network_param_file_cmd) - ld.add_action(darknet_ros_cmd) - ld.add_action(camera) - - return ld + return LaunchDescription([ + darknet_ros_launch, + camera, + ]) \ No newline at end of file diff --git a/darknet_ros/launch/yolov2-tiny.launch.py b/darknet_ros/launch/yolov2-tiny.launch.py index 4d0c3c08f..cf36058b2 100644 --- a/darknet_ros/launch/yolov2-tiny.launch.py +++ b/darknet_ros/launch/yolov2-tiny.launch.py @@ -10,54 +10,24 @@ def generate_launch_description(): darknet_ros_share_dir = get_package_share_directory('darknet_ros') - - 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') - - declare_image_cmd = DeclareLaunchArgument( - 'image', - 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') - declare_yolo_config_path_cmd = DeclareLaunchArgument( - 'yolo_config_path', - default_value = darknet_ros_share_dir + '/yolo_network_config/cfg', - description = 'Path to yolo config') - declare_ros_param_file_cmd = DeclareLaunchArgument( - 'ros_param_file', - default_value = darknet_ros_share_dir + '/config/ros.yaml', - 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') - - darknet_ros_cmd = Node( - package='darknet_ros', - node_executable='darknet_ros', - node_name='darknet_ros', - output='screen', - parameters=[ros_param_file, network_param_file, - { - "config_path": yolo_config_path, - "weights_path": yolo_weights_path, - }, + network_param_file = darknet_ros_share_dir + '/config/yolov2-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", + node_executable="v4l2_camera_node", + # node_namespace="camera/rgb", + parameters=[ + {'video_device' : "/dev/video0"}, ]) - - ld = LaunchDescription() - - ld.add_action(declare_image_cmd) - ld.add_action(declare_yolo_weights_path_cmd) - ld.add_action(declare_yolo_config_path_cmd) - ld.add_action(declare_ros_param_file_cmd) - ld.add_action(declare_network_param_file_cmd) - ld.add_action(darknet_ros_cmd) - - return ld + return LaunchDescription([ + darknet_ros_launch, + camera, + ]) \ No newline at end of file diff --git a/darknet_ros/launch/yolov4-csp.launch.py b/darknet_ros/launch/yolov4-csp.launch.py index 56ea045ff..3635d9f83 100644 --- a/darknet_ros/launch/yolov4-csp.launch.py +++ b/darknet_ros/launch/yolov4-csp.launch.py @@ -10,54 +10,24 @@ def generate_launch_description(): darknet_ros_share_dir = get_package_share_directory('darknet_ros') - - 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/yolov4-csp.yaml') - - declare_image_cmd = DeclareLaunchArgument( - 'image', - 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') - declare_yolo_config_path_cmd = DeclareLaunchArgument( - 'yolo_config_path', - default_value = darknet_ros_share_dir + '/yolo_network_config/cfg', - description = 'Path to yolo config') - declare_ros_param_file_cmd = DeclareLaunchArgument( - 'ros_param_file', - default_value = darknet_ros_share_dir + '/config/ros.yaml', - description = 'Path to file with ROS related config') - declare_network_param_file_cmd = DeclareLaunchArgument( - 'network_param_file', - default_value = darknet_ros_share_dir + '/config/yolov4-csp.yaml', - description = 'Path to file with network param file') - - darknet_ros_cmd = Node( - package='darknet_ros', - node_executable='darknet_ros', - node_name='darknet_ros', - output='screen', - parameters=[ros_param_file, network_param_file, - { - "config_path": yolo_config_path, - "weights_path": yolo_weights_path, - }, + 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", + node_executable="v4l2_camera_node", + # node_namespace="camera/rgb", + parameters=[ + {'video_device' : "/dev/video0"}, ]) - - ld = LaunchDescription() - - ld.add_action(declare_image_cmd) - ld.add_action(declare_yolo_weights_path_cmd) - ld.add_action(declare_yolo_config_path_cmd) - ld.add_action(declare_ros_param_file_cmd) - ld.add_action(declare_network_param_file_cmd) - ld.add_action(darknet_ros_cmd) - - return ld + return LaunchDescription([ + darknet_ros_launch, + # 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 index 6eb213889..8dd69e86a 100644 --- a/darknet_ros/launch/yolov4-tiny.launch.py +++ b/darknet_ros/launch/yolov4-tiny.launch.py @@ -10,54 +10,24 @@ def generate_launch_description(): darknet_ros_share_dir = get_package_share_directory('darknet_ros') - - 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/yolov4-tiny.yaml') - - declare_image_cmd = DeclareLaunchArgument( - 'image', - 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') - declare_yolo_config_path_cmd = DeclareLaunchArgument( - 'yolo_config_path', - default_value = darknet_ros_share_dir + '/yolo_network_config/cfg', - description = 'Path to yolo config') - declare_ros_param_file_cmd = DeclareLaunchArgument( - 'ros_param_file', - default_value = darknet_ros_share_dir + '/config/ros.yaml', - description = 'Path to file with ROS related config') - declare_network_param_file_cmd = DeclareLaunchArgument( - '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', - output='screen', - parameters=[ros_param_file, network_param_file, - { - "config_path": yolo_config_path, - "weights_path": yolo_weights_path, - }, + 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", + node_executable="v4l2_camera_node", + # node_namespace="camera/rgb", + parameters=[ + {'video_device' : "/dev/video0"}, ]) - - ld = LaunchDescription() - - ld.add_action(declare_image_cmd) - ld.add_action(declare_yolo_weights_path_cmd) - ld.add_action(declare_yolo_config_path_cmd) - ld.add_action(declare_ros_param_file_cmd) - ld.add_action(declare_network_param_file_cmd) - ld.add_action(darknet_ros_cmd) - - return ld + return LaunchDescription([ + darknet_ros_launch, + # camera, + ]) \ No newline at end of file diff --git a/darknet_ros/launch/yolov4.launch.py b/darknet_ros/launch/yolov4.launch.py index 0591d5afe..8dd69e86a 100644 --- a/darknet_ros/launch/yolov4.launch.py +++ b/darknet_ros/launch/yolov4.launch.py @@ -10,54 +10,24 @@ def generate_launch_description(): darknet_ros_share_dir = get_package_share_directory('darknet_ros') - - 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/yolov4.yaml') - - declare_image_cmd = DeclareLaunchArgument( - 'image', - 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') - declare_yolo_config_path_cmd = DeclareLaunchArgument( - 'yolo_config_path', - default_value = darknet_ros_share_dir + '/yolo_network_config/cfg', - description = 'Path to yolo config') - declare_ros_param_file_cmd = DeclareLaunchArgument( - 'ros_param_file', - default_value = darknet_ros_share_dir + '/config/ros.yaml', - description = 'Path to file with ROS related config') - declare_network_param_file_cmd = DeclareLaunchArgument( - 'network_param_file', - default_value = darknet_ros_share_dir + '/config/yolov4.yaml', - description = 'Path to file with network param file') - - darknet_ros_cmd = Node( - package='darknet_ros', - node_executable='darknet_ros', - node_name='darknet_ros', - output='screen', - parameters=[ros_param_file, network_param_file, - { - "config_path": yolo_config_path, - "weights_path": yolo_weights_path, - }, + 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", + node_executable="v4l2_camera_node", + # node_namespace="camera/rgb", + parameters=[ + {'video_device' : "/dev/video0"}, ]) - - ld = LaunchDescription() - - ld.add_action(declare_image_cmd) - ld.add_action(declare_yolo_weights_path_cmd) - ld.add_action(declare_yolo_config_path_cmd) - ld.add_action(declare_ros_param_file_cmd) - ld.add_action(declare_network_param_file_cmd) - ld.add_action(darknet_ros_cmd) - - return ld + return LaunchDescription([ + darknet_ros_launch, + # camera, + ]) \ No newline at end of file From fd6ff4a33579e7828e6b8b19a5b3728a2a6ae2da Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Thu, 12 Aug 2021 16:19:27 +0900 Subject: [PATCH 50/64] fix launch --- darknet_ros/launch/demo-v4-csp.launch.py | 11 ++--------- darknet_ros/launch/demo-v4-tiny.launch.py | 11 ++--------- darknet_ros/launch/demo-v4.launch.py | 11 ++--------- darknet_ros/launch/demo-v4x-mish.launch.py | 11 ++--------- darknet_ros/launch/yolov2-tiny.launch.py | 11 ++--------- darknet_ros/launch/yolov4-csp.launch.py | 11 ++--------- darknet_ros/launch/yolov4-tiny.launch.py | 11 ++--------- darknet_ros/launch/yolov4.launch.py | 11 ++--------- 8 files changed, 16 insertions(+), 72 deletions(-) diff --git a/darknet_ros/launch/demo-v4-csp.launch.py b/darknet_ros/launch/demo-v4-csp.launch.py index 6ddcb4371..1ed229291 100644 --- a/darknet_ros/launch/demo-v4-csp.launch.py +++ b/darknet_ros/launch/demo-v4-csp.launch.py @@ -1,11 +1,7 @@ -import os - from ament_index_python.packages import get_package_share_directory - from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, SetEnvironmentVariable +from launch.actions import IncludeLaunchDescription from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node def generate_launch_description(): @@ -14,15 +10,12 @@ def generate_launch_description(): darknet_ros_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource([darknet_ros_share_dir + '/launch/darknet_ros.launch.py']), - launch_arguments={ - 'network_param_file': network_param_file, - }.items() + launch_arguments={'network_param_file': network_param_file}.items() ) camera = Node( package="v4l2_camera", node_executable="v4l2_camera_node", - # node_namespace="camera/rgb", parameters=[ {'video_device' : "/dev/video0"}, ]) diff --git a/darknet_ros/launch/demo-v4-tiny.launch.py b/darknet_ros/launch/demo-v4-tiny.launch.py index 235d06db5..d3c8f34c2 100644 --- a/darknet_ros/launch/demo-v4-tiny.launch.py +++ b/darknet_ros/launch/demo-v4-tiny.launch.py @@ -1,11 +1,7 @@ -import os - from ament_index_python.packages import get_package_share_directory - from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, SetEnvironmentVariable +from launch.actions import IncludeLaunchDescription from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node def generate_launch_description(): @@ -14,15 +10,12 @@ def generate_launch_description(): darknet_ros_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource([darknet_ros_share_dir + '/launch/darknet_ros.launch.py']), - launch_arguments={ - 'network_param_file': network_param_file, - }.items() + launch_arguments={'network_param_file': network_param_file}.items() ) camera = Node( package="v4l2_camera", node_executable="v4l2_camera_node", - # node_namespace="camera/rgb", parameters=[ {'video_device' : "/dev/video0"}, ]) diff --git a/darknet_ros/launch/demo-v4.launch.py b/darknet_ros/launch/demo-v4.launch.py index 61e3cd808..f890954da 100644 --- a/darknet_ros/launch/demo-v4.launch.py +++ b/darknet_ros/launch/demo-v4.launch.py @@ -1,11 +1,7 @@ -import os - from ament_index_python.packages import get_package_share_directory - from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, SetEnvironmentVariable +from launch.actions import IncludeLaunchDescription from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node def generate_launch_description(): @@ -14,15 +10,12 @@ def generate_launch_description(): darknet_ros_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource([darknet_ros_share_dir + '/launch/darknet_ros.launch.py']), - launch_arguments={ - 'network_param_file': network_param_file, - }.items() + launch_arguments={'network_param_file': network_param_file}.items() ) camera = Node( package="v4l2_camera", node_executable="v4l2_camera_node", - # node_namespace="camera/rgb", parameters=[ {'video_device' : "/dev/video0"}, ]) diff --git a/darknet_ros/launch/demo-v4x-mish.launch.py b/darknet_ros/launch/demo-v4x-mish.launch.py index ceccfce33..a47796b33 100644 --- a/darknet_ros/launch/demo-v4x-mish.launch.py +++ b/darknet_ros/launch/demo-v4x-mish.launch.py @@ -1,11 +1,7 @@ -import os - from ament_index_python.packages import get_package_share_directory - from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, SetEnvironmentVariable +from launch.actions import IncludeLaunchDescription from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node def generate_launch_description(): @@ -14,15 +10,12 @@ def generate_launch_description(): darknet_ros_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource([darknet_ros_share_dir + '/launch/darknet_ros.launch.py']), - launch_arguments={ - 'network_param_file': network_param_file, - }.items() + launch_arguments={'network_param_file': network_param_file}.items() ) camera = Node( package="v4l2_camera", node_executable="v4l2_camera_node", - # node_namespace="camera/rgb", parameters=[ {'video_device' : "/dev/video0"}, ]) diff --git a/darknet_ros/launch/yolov2-tiny.launch.py b/darknet_ros/launch/yolov2-tiny.launch.py index cf36058b2..4f40eb156 100644 --- a/darknet_ros/launch/yolov2-tiny.launch.py +++ b/darknet_ros/launch/yolov2-tiny.launch.py @@ -1,11 +1,7 @@ -import os - from ament_index_python.packages import get_package_share_directory - from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, SetEnvironmentVariable +from launch.actions import IncludeLaunchDescription from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node def generate_launch_description(): @@ -14,15 +10,12 @@ def generate_launch_description(): darknet_ros_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource([darknet_ros_share_dir + '/launch/darknet_ros.launch.py']), - launch_arguments={ - 'network_param_file': network_param_file, - }.items() + launch_arguments={'network_param_file': network_param_file}.items() ) camera = Node( package="v4l2_camera", node_executable="v4l2_camera_node", - # node_namespace="camera/rgb", parameters=[ {'video_device' : "/dev/video0"}, ]) diff --git a/darknet_ros/launch/yolov4-csp.launch.py b/darknet_ros/launch/yolov4-csp.launch.py index 3635d9f83..68d7ffaf8 100644 --- a/darknet_ros/launch/yolov4-csp.launch.py +++ b/darknet_ros/launch/yolov4-csp.launch.py @@ -1,11 +1,7 @@ -import os - from ament_index_python.packages import get_package_share_directory - from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, SetEnvironmentVariable +from launch.actions import IncludeLaunchDescription from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node def generate_launch_description(): @@ -14,15 +10,12 @@ def generate_launch_description(): darknet_ros_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource([darknet_ros_share_dir + '/launch/darknet_ros.launch.py']), - launch_arguments={ - 'network_param_file': network_param_file, - }.items() + launch_arguments={'network_param_file': network_param_file}.items() ) camera = Node( package="v4l2_camera", node_executable="v4l2_camera_node", - # node_namespace="camera/rgb", parameters=[ {'video_device' : "/dev/video0"}, ]) diff --git a/darknet_ros/launch/yolov4-tiny.launch.py b/darknet_ros/launch/yolov4-tiny.launch.py index 8dd69e86a..e0a49a67d 100644 --- a/darknet_ros/launch/yolov4-tiny.launch.py +++ b/darknet_ros/launch/yolov4-tiny.launch.py @@ -1,11 +1,7 @@ -import os - from ament_index_python.packages import get_package_share_directory - from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, SetEnvironmentVariable +from launch.actions import IncludeLaunchDescription from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node def generate_launch_description(): @@ -14,15 +10,12 @@ def generate_launch_description(): darknet_ros_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource([darknet_ros_share_dir + '/launch/darknet_ros.launch.py']), - launch_arguments={ - 'network_param_file': network_param_file, - }.items() + launch_arguments={'network_param_file': network_param_file}.items() ) camera = Node( package="v4l2_camera", node_executable="v4l2_camera_node", - # node_namespace="camera/rgb", parameters=[ {'video_device' : "/dev/video0"}, ]) diff --git a/darknet_ros/launch/yolov4.launch.py b/darknet_ros/launch/yolov4.launch.py index 8dd69e86a..e0a49a67d 100644 --- a/darknet_ros/launch/yolov4.launch.py +++ b/darknet_ros/launch/yolov4.launch.py @@ -1,11 +1,7 @@ -import os - from ament_index_python.packages import get_package_share_directory - from launch import LaunchDescription -from launch.actions import DeclareLaunchArgument, IncludeLaunchDescription, SetEnvironmentVariable +from launch.actions import IncludeLaunchDescription from launch.launch_description_sources import PythonLaunchDescriptionSource -from launch.substitutions import LaunchConfiguration from launch_ros.actions import Node def generate_launch_description(): @@ -14,15 +10,12 @@ def generate_launch_description(): darknet_ros_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource([darknet_ros_share_dir + '/launch/darknet_ros.launch.py']), - launch_arguments={ - 'network_param_file': network_param_file, - }.items() + launch_arguments={'network_param_file': network_param_file}.items() ) camera = Node( package="v4l2_camera", node_executable="v4l2_camera_node", - # node_namespace="camera/rgb", parameters=[ {'video_device' : "/dev/video0"}, ]) From 8e361d26ff4659be41f4ca9a803efd5a28f23dab Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Thu, 12 Aug 2021 16:30:59 +0900 Subject: [PATCH 51/64] update some files --- README.md | 2 - YOLOv4.md | 43 ---------------------- darknet_ros/CMakeLists.txt | 28 +++++++------- darknet_ros/launch/darknet_ros.launch.py | 4 +- darknet_ros/launch/demo-v4-csp.launch.py | 26 ------------- darknet_ros/launch/demo-v4-tiny.launch.py | 26 ------------- darknet_ros/launch/demo-v4.launch.py | 26 ------------- darknet_ros/launch/demo-v4x-mish.launch.py | 26 ------------- darknet_ros/launch/yolov2-tiny.launch.py | 26 ------------- darknet_ros/launch/yolov4-csp.launch.py | 26 ------------- darknet_ros/launch/yolov4-tiny.launch.py | 3 +- darknet_ros/launch/yolov4.launch.py | 5 ++- 12 files changed, 21 insertions(+), 220 deletions(-) delete mode 100644 YOLOv4.md delete mode 100644 darknet_ros/launch/demo-v4-csp.launch.py delete mode 100644 darknet_ros/launch/demo-v4-tiny.launch.py delete mode 100644 darknet_ros/launch/demo-v4.launch.py delete mode 100644 darknet_ros/launch/demo-v4x-mish.launch.py delete mode 100644 darknet_ros/launch/yolov2-tiny.launch.py delete mode 100644 darknet_ros/launch/yolov4-csp.launch.py diff --git a/README.md b/README.md index 47c9dce4e..af6b4de2e 100644 --- a/README.md +++ b/README.md @@ -1,7 +1,5 @@ # YOLO ROS: Real-Time Object Detection for ROS -Darknet_ros + ROS2 Foxy + YOLO v4 Installation is [here (Jump to Ar-Ray-code/darknet_ros)](https://github.com/Ar-Ray-code/darknet_ros/blob/master/YOLOv4.md). - ## 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/). diff --git a/YOLOv4.md b/YOLOv4.md deleted file mode 100644 index de92d1915..000000000 --- a/YOLOv4.md +++ /dev/null @@ -1,43 +0,0 @@ -# Darknet ROS + YOLO v4 + ROS-Foxy - -Writer: [Ar-Ray](https://github.com/Ar-Ray-code) - -## Requirements - -- ROS-Foxy -- CUDA 11.2 -- OpenCV4 - -## Installation - -```bash -$ cd -$ mkdir -p ros2_ws/src -$ cd ros2_ws/src -$ git clone --recursive https://github.com/Ar-Ray-code/darknet_ros.git -$ darknet_ros/rm_darknet_CMakeLists.sh -$ source /opt/ros/foxy/setup.bash -$ cd ~/ros2_ws -$ colcon build --symlink-install -``` - - - -## Execute YOLO v4 - -Terminal 1 - -```bash -$ source /opt/ros/foxy/setup.bash -$ source ~/ros2_ws/install/local_setup.bash -$ ros2 run v4l2_camera v4l2_camera_node --ros-args -r __ns:=/camera/rgb -``` - -Terminal 2 - -```bash -$ source /opt/ros/foxy/setup.bash -$ source ~/ros2_ws/install/local_setup.bash -$ ros2 run darknet_ros yolov4.launch.py -``` - diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 4f6540d50..353eebe3c 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -9,7 +9,7 @@ set(CMAKE_CXX_STANDARD 17) set(CUDA_ENABLE ON) set(CUDNN_ENABLE OFF) # set(CUDNN_ENABLE ON) -set(FP16_ENABLE ON) +set(FP16_ENABLE OFF) # Jetson AGX Xavier & TITAN V is under version of Turing. So, please set manually. # Turing or Ampere GPUs, FP16 is automatically enabled. @@ -39,7 +39,7 @@ if (CUDA_FOUND) -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,compute_61] - # -gencode arch=compute_72,code=[sm_72,compute_72] # Jetson AGX Xavier or TITAN V + -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_86,code=[sm_86,compute_86] # GeForce RTX 3000 Series ) @@ -308,12 +308,12 @@ set(PATH "${CMAKE_CURRENT_SOURCE_DIR}/yolo_network_config/weights") # 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() +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() # Download yolov4-tiny.weights set(FILE "${PATH}/yolov4-tiny.weights") @@ -324,12 +324,12 @@ if (NOT EXISTS "${FILE}") endif() # Download yolov4-csp.weights -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() +# 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() install(DIRECTORY yolo_network_config/cfg yolo_network_config/weights DESTINATION share/${PROJECT_NAME}/yolo_network_config/) diff --git a/darknet_ros/launch/darknet_ros.launch.py b/darknet_ros/launch/darknet_ros.launch.py index 8d00fe302..b2bd6b57f 100644 --- a/darknet_ros/launch/darknet_ros.launch.py +++ b/darknet_ros/launch/darknet_ros.launch.py @@ -15,7 +15,7 @@ def generate_launch_description(): 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', @@ -35,7 +35,7 @@ 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', + default_value = darknet_ros_share_dir + '/config/yolov4-tiny.yaml', description = 'Path to file with network param file') darknet_ros_cmd = Node( diff --git a/darknet_ros/launch/demo-v4-csp.launch.py b/darknet_ros/launch/demo-v4-csp.launch.py deleted file mode 100644 index 1ed229291..000000000 --- a/darknet_ros/launch/demo-v4-csp.launch.py +++ /dev/null @@ -1,26 +0,0 @@ -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", - node_executable="v4l2_camera_node", - parameters=[ - {'video_device' : "/dev/video0"}, - ]) - - return LaunchDescription([ - darknet_ros_launch, - camera, - ]) \ No newline at end of file diff --git a/darknet_ros/launch/demo-v4-tiny.launch.py b/darknet_ros/launch/demo-v4-tiny.launch.py deleted file mode 100644 index d3c8f34c2..000000000 --- a/darknet_ros/launch/demo-v4-tiny.launch.py +++ /dev/null @@ -1,26 +0,0 @@ -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", - node_executable="v4l2_camera_node", - parameters=[ - {'video_device' : "/dev/video0"}, - ]) - - return LaunchDescription([ - darknet_ros_launch, - camera, - ]) \ No newline at end of file diff --git a/darknet_ros/launch/demo-v4.launch.py b/darknet_ros/launch/demo-v4.launch.py deleted file mode 100644 index f890954da..000000000 --- a/darknet_ros/launch/demo-v4.launch.py +++ /dev/null @@ -1,26 +0,0 @@ -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.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", - node_executable="v4l2_camera_node", - parameters=[ - {'video_device' : "/dev/video0"}, - ]) - - return LaunchDescription([ - darknet_ros_launch, - camera, - ]) \ No newline at end of file diff --git a/darknet_ros/launch/demo-v4x-mish.launch.py b/darknet_ros/launch/demo-v4x-mish.launch.py deleted file mode 100644 index a47796b33..000000000 --- a/darknet_ros/launch/demo-v4x-mish.launch.py +++ /dev/null @@ -1,26 +0,0 @@ -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-mish.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", - node_executable="v4l2_camera_node", - parameters=[ - {'video_device' : "/dev/video0"}, - ]) - - return LaunchDescription([ - darknet_ros_launch, - camera, - ]) \ No newline at end of file diff --git a/darknet_ros/launch/yolov2-tiny.launch.py b/darknet_ros/launch/yolov2-tiny.launch.py deleted file mode 100644 index 4f40eb156..000000000 --- a/darknet_ros/launch/yolov2-tiny.launch.py +++ /dev/null @@ -1,26 +0,0 @@ -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/yolov2-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", - node_executable="v4l2_camera_node", - parameters=[ - {'video_device' : "/dev/video0"}, - ]) - - return LaunchDescription([ - darknet_ros_launch, - camera, - ]) \ No newline at end of file diff --git a/darknet_ros/launch/yolov4-csp.launch.py b/darknet_ros/launch/yolov4-csp.launch.py deleted file mode 100644 index 68d7ffaf8..000000000 --- a/darknet_ros/launch/yolov4-csp.launch.py +++ /dev/null @@ -1,26 +0,0 @@ -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", - node_executable="v4l2_camera_node", - parameters=[ - {'video_device' : "/dev/video0"}, - ]) - - return LaunchDescription([ - darknet_ros_launch, - # 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 index e0a49a67d..a321129fb 100644 --- a/darknet_ros/launch/yolov4-tiny.launch.py +++ b/darknet_ros/launch/yolov4-tiny.launch.py @@ -22,5 +22,6 @@ def generate_launch_description(): return LaunchDescription([ darknet_ros_launch, - # camera, + # 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.launch.py b/darknet_ros/launch/yolov4.launch.py index e0a49a67d..0ce6e0bb5 100644 --- a/darknet_ros/launch/yolov4.launch.py +++ b/darknet_ros/launch/yolov4.launch.py @@ -6,7 +6,7 @@ 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' + network_param_file = darknet_ros_share_dir + '/config/yolov4.yaml' darknet_ros_launch = IncludeLaunchDescription( PythonLaunchDescriptionSource([darknet_ros_share_dir + '/launch/darknet_ros.launch.py']), @@ -22,5 +22,6 @@ def generate_launch_description(): return LaunchDescription([ darknet_ros_launch, - # camera, + # if you want to disable camera node, remove the following line. + camera, ]) \ No newline at end of file From 3c4081877e6b677c204397a74cbaa11d3094aa2c Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Thu, 12 Aug 2021 16:45:54 +0900 Subject: [PATCH 52/64] delete some config --- darknet_ros/config/yolov2-tiny-voc.yaml | 33 - darknet_ros/config/yolov2-voc.yaml | 32 - darknet_ros/config/yolov2.yaml | 92 -- darknet_ros/config/yolov3-voc.yaml | 32 - darknet_ros/config/yolov4-csp.yaml | 91 -- darknet_ros/config/yolov4x-mish.yaml | 91 -- .../cfg/yolov2-tiny-voc.cfg | 138 -- .../yolo_network_config/cfg/yolov2-voc.cfg | 258 --- .../yolo_network_config/cfg/yolov2.cfg | 258 --- .../yolo_network_config/cfg/yolov3-voc.cfg | 785 --------- .../yolo_network_config/cfg/yolov4-csp.cfg | 1279 --------------- .../yolo_network_config/cfg/yolov4x-mish.cfg | 1436 ----------------- 12 files changed, 4525 deletions(-) delete mode 100644 darknet_ros/config/yolov2-tiny-voc.yaml delete mode 100644 darknet_ros/config/yolov2-voc.yaml delete mode 100644 darknet_ros/config/yolov2.yaml delete mode 100644 darknet_ros/config/yolov3-voc.yaml delete mode 100644 darknet_ros/config/yolov4-csp.yaml delete mode 100644 darknet_ros/config/yolov4x-mish.yaml delete mode 100644 darknet_ros/yolo_network_config/cfg/yolov2-tiny-voc.cfg delete mode 100644 darknet_ros/yolo_network_config/cfg/yolov2-voc.cfg delete mode 100644 darknet_ros/yolo_network_config/cfg/yolov2.cfg delete mode 100644 darknet_ros/yolo_network_config/cfg/yolov3-voc.cfg delete mode 100644 darknet_ros/yolo_network_config/cfg/yolov4-csp.cfg delete mode 100644 darknet_ros/yolo_network_config/cfg/yolov4x-mish.cfg 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/yolov2.yaml b/darknet_ros/config/yolov2.yaml deleted file mode 100644 index a6e4d67de..000000000 --- a/darknet_ros/config/yolov2.yaml +++ /dev/null @@ -1,92 +0,0 @@ -darknet_ros: - ros__parameters: - yolo_model: - - config_file: - name: yolov2.cfg - weight_file: - name: yolov2.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/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/yolov4-csp.yaml b/darknet_ros/config/yolov4-csp.yaml deleted file mode 100644 index f4b11035b..000000000 --- a/darknet_ros/config/yolov4-csp.yaml +++ /dev/null @@ -1,91 +0,0 @@ -darknet_ros: - ros__parameters: - yolo_model: - config_file: - name: yolov4-csp.cfg - weight_file: - name: yolov4-csp.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/yolov4x-mish.yaml b/darknet_ros/config/yolov4x-mish.yaml deleted file mode 100644 index d22686d7a..000000000 --- a/darknet_ros/config/yolov4x-mish.yaml +++ /dev/null @@ -1,91 +0,0 @@ -darknet_ros: - ros__parameters: - yolo_model: - config_file: - name: yolov4x-mish.cfg - weight_file: - name: yolov4x-mish.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/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/yolov2.cfg b/darknet_ros/yolo_network_config/cfg/yolov2.cfg deleted file mode 100644 index 2a0cd98fb..000000000 --- a/darknet_ros/yolo_network_config/cfg/yolov2.cfg +++ /dev/null @@ -1,258 +0,0 @@ -[net] -# Testing -batch=1 -subdivisions=1 -# Training -# batch=64 -# subdivisions=8 -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 -burn_in=1000 -max_batches = 500200 -policy=steps -steps=400000,450000 -scales=.1,.1 - -[convolutional] -batch_normalize=1 -filters=32 -size=3 -stride=1 -pad=1 -activation=leaky - -[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=425 -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 -classes=80 -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/yolov3-voc.cfg b/darknet_ros/yolo_network_config/cfg/yolov3-voc.cfg deleted file mode 100644 index 3f3e8dfb3..000000000 --- a/darknet_ros/yolo_network_config/cfg/yolov3-voc.cfg +++ /dev/null @@ -1,785 +0,0 @@ -[net] -# Testing - batch=1 - subdivisions=1 -# Training -# batch=64 -# subdivisions=16 -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 -burn_in=1000 -max_batches = 50200 -policy=steps -steps=40000,45000 -scales=.1,.1 - - - -[convolutional] -batch_normalize=1 -filters=32 -size=3 -stride=1 -pad=1 -activation=leaky - -# Downsample - -[convolutional] -batch_normalize=1 -filters=64 -size=3 -stride=2 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=32 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=64 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -# Downsample - -[convolutional] -batch_normalize=1 -filters=128 -size=3 -stride=2 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=64 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=128 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=64 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=128 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -# Downsample - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=2 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -# Downsample - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=2 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -# Downsample - -[convolutional] -batch_normalize=1 -filters=1024 -size=3 -stride=2 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=1024 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=512 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=1024 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=512 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=1024 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=512 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=1024 -size=3 -stride=1 -pad=1 -activation=leaky - -[shortcut] -from=-3 -activation=linear - -###################### - -[convolutional] -batch_normalize=1 -filters=512 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=1024 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=1024 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=512 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=1024 -activation=leaky - -[convolutional] -size=1 -stride=1 -pad=1 -filters=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 -stride=1 -pad=1 -activation=leaky - -[upsample] -stride=2 - -[route] -layers = -1, 61 - - - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=512 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=512 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=256 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=512 -activation=leaky - -[convolutional] -size=1 -stride=1 -pad=1 -filters=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 - -[route] -layers = -4 - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[upsample] -stride=2 - -[route] -layers = -1, 36 - - - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=256 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=256 -activation=leaky - -[convolutional] -batch_normalize=1 -filters=128 -size=1 -stride=1 -pad=1 -activation=leaky - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=256 -activation=leaky - -[convolutional] -size=1 -stride=1 -pad=1 -filters=75 -activation=linear - -[yolo] -mask = 0,1,2 -anchors = 10,13, 16,30, 33,23, 30,61, 62,45, 59,119, 116,90, 156,198, 373,326 -classes=20 -num=9 -jitter=.3 -ignore_thresh = .5 -truth_thresh = 1 -random=1 - diff --git a/darknet_ros/yolo_network_config/cfg/yolov4-csp.cfg b/darknet_ros/yolo_network_config/cfg/yolov4-csp.cfg deleted file mode 100644 index f46989fd0..000000000 --- a/darknet_ros/yolo_network_config/cfg/yolov4-csp.cfg +++ /dev/null @@ -1,1279 +0,0 @@ -[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 \ No newline at end of file diff --git a/darknet_ros/yolo_network_config/cfg/yolov4x-mish.cfg b/darknet_ros/yolo_network_config/cfg/yolov4x-mish.cfg deleted file mode 100644 index ab598f6e7..000000000 --- a/darknet_ros/yolo_network_config/cfg/yolov4x-mish.cfg +++ /dev/null @@ -1,1436 +0,0 @@ -[net] -# Testing -#batch=1 -#subdivisions=1 -# Training -batch=1 -subdivisions=1 -width=640 -height=640 -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 - -#optimized_memory=1 - -[convolutional] -batch_normalize=1 -filters=32 -size=3 -stride=1 -pad=1 -activation=mish - -# Downsample - -[convolutional] -batch_normalize=1 -filters=80 -size=3 -stride=2 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=40 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=80 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -# Downsample - -[convolutional] -batch_normalize=1 -filters=160 -size=3 -stride=2 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=80 -size=1 -stride=1 -pad=1 -activation=mish - -[route] -layers = -2 - -[convolutional] -batch_normalize=1 -filters=80 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=80 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=80 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=80 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=80 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=80 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=80 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=80 -size=1 -stride=1 -pad=1 -activation=mish - -[route] -layers = -1,-13 - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -# Downsample - -[convolutional] -batch_normalize=1 -filters=320 -size=3 -stride=2 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -[route] -layers = -2 - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=160 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=160 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=160 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=160 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=160 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=160 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=160 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=160 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=160 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=160 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -[route] -layers = -1,-34 - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -# Downsample - -[convolutional] -batch_normalize=1 -filters=640 -size=3 -stride=2 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[route] -layers = -2 - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=320 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=320 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=320 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=320 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=320 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=320 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=320 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=320 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=320 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=320 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[route] -layers = -1,-34 - -[convolutional] -batch_normalize=1 -filters=640 -size=1 -stride=1 -pad=1 -activation=mish - -# Downsample - -[convolutional] -batch_normalize=1 -filters=1280 -size=3 -stride=2 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=640 -size=1 -stride=1 -pad=1 -activation=mish - -[route] -layers = -2 - -[convolutional] -batch_normalize=1 -filters=640 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=640 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=640 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=640 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=640 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=640 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=640 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=640 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=640 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=640 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=640 -size=3 -stride=1 -pad=1 -activation=mish - -[shortcut] -from=-3 -activation=linear - -[convolutional] -batch_normalize=1 -filters=640 -size=1 -stride=1 -pad=1 -activation=mish - -[route] -layers = -1,-19 - -[convolutional] -batch_normalize=1 -filters=1280 -size=1 -stride=1 -pad=1 -activation=mish - -########################## 6 0 6 6 3 - -[convolutional] -batch_normalize=1 -filters=640 -size=1 -stride=1 -pad=1 -activation=mish - -[route] -layers = -2 - -[convolutional] -batch_normalize=1 -filters=640 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=640 -activation=mish - -[convolutional] -batch_normalize=1 -filters=640 -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=640 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=640 -activation=mish - -[convolutional] -batch_normalize=1 -filters=640 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=640 -activation=mish - -[route] -layers = -1, -15 - -[convolutional] -batch_normalize=1 -filters=640 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[upsample] -stride=2 - -[route] -layers = 94 - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[route] -layers = -1, -3 - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[route] -layers = -2 - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=320 -activation=mish - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=320 -activation=mish - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=320 -activation=mish - -[route] -layers = -1, -8 - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -[upsample] -stride=2 - -[route] -layers = 57 - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -[route] -layers = -1, -3 - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -[route] -layers = -2 - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=160 -activation=mish - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=160 -activation=mish - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=160 -activation=mish - -[route] -layers = -1, -8 - -[convolutional] -batch_normalize=1 -filters=160 -size=1 -stride=1 -pad=1 -activation=mish -stopbackward=800 - -########################## - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=320 -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=320 -activation=mish - -[route] -layers = -1, -22 - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[route] -layers = -2 - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=320 -activation=mish - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=320 -activation=mish - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=320 -activation=mish - -[route] -layers = -1,-8 - -[convolutional] -batch_normalize=1 -filters=320 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=640 -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=640 -activation=mish - -[route] -layers = -1, -55 - -[convolutional] -batch_normalize=1 -filters=640 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -filters=640 -size=1 -stride=1 -pad=1 -activation=mish - -[route] -layers = -2 - -[convolutional] -batch_normalize=1 -filters=640 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=640 -activation=mish - -[convolutional] -batch_normalize=1 -filters=640 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=640 -activation=mish - -[convolutional] -batch_normalize=1 -filters=640 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=640 -activation=mish - -[route] -layers = -1,-8 - -[convolutional] -batch_normalize=1 -filters=640 -size=1 -stride=1 -pad=1 -activation=mish - -[convolutional] -batch_normalize=1 -size=3 -stride=1 -pad=1 -filters=1280 -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 From 62197c1cae0ecd4cea1bf6ae29a280567363010f Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Sat, 14 Aug 2021 02:05:47 +0900 Subject: [PATCH 53/64] cpu is ok --- darknet_ros/CMakeLists.txt | 7 +------ 1 file changed, 1 insertion(+), 6 deletions(-) diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 353eebe3c..413f2b51a 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -244,12 +244,9 @@ 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) @@ -273,7 +270,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) @@ -367,7 +363,6 @@ install(DIRECTORY launch config DESTINATION share/${PROJECT_NAME}/) ament_export_include_directories(include) ament_export_libraries(${PROJECT_NAME}_lib) -ament_export_libraries(${PROJECT_NAME}_core_lib) ament_export_dependencies(${dependencies}) ament_package() From 706dce051f4dacc345dd3ebf1166df34d35e05c6 Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Sat, 14 Aug 2021 02:18:21 +0900 Subject: [PATCH 54/64] cpu-openmp --- darknet_ros/CMakeLists.txt | 9 ++++++++- 1 file changed, 8 insertions(+), 1 deletion(-) diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 413f2b51a..5ffb103c6 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -7,7 +7,7 @@ set(CMAKE_CXX_STANDARD 17) # USER SETTINGS ================================================================= -set(CUDA_ENABLE ON) +set(CUDA_ENABLE OFF) set(CUDNN_ENABLE OFF) # set(CUDNN_ENABLE ON) set(FP16_ENABLE OFF) @@ -258,6 +258,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 From b2f7e9e133165675781d43e08f805f7efb072f0a Mon Sep 17 00:00:00 2001 From: Ar-Ray <67567093+Ar-Ray-code@users.noreply.github.com> Date: Wed, 29 Sep 2021 22:53:37 +0900 Subject: [PATCH 55/64] CUDA = ON --- darknet_ros/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 5ffb103c6..bc93a883a 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -7,7 +7,7 @@ set(CMAKE_CXX_STANDARD 17) # USER SETTINGS ================================================================= -set(CUDA_ENABLE OFF) +set(CUDA_ENABLE ON) set(CUDNN_ENABLE OFF) # set(CUDNN_ENABLE ON) set(FP16_ENABLE OFF) From da4c16fd2d84f0e225cecf6436576d6b0502fb6a Mon Sep 17 00:00:00 2001 From: Ar-Ray <67567093+Ar-Ray-code@users.noreply.github.com> Date: Sat, 4 Dec 2021 15:52:00 +0900 Subject: [PATCH 56/64] cudnn + fp16 -> on --- darknet_ros/CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index bc93a883a..91a9bf43b 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -8,8 +8,8 @@ set(CMAKE_CXX_STANDARD 17) # USER SETTINGS ================================================================= set(CUDA_ENABLE ON) -set(CUDNN_ENABLE OFF) # set(CUDNN_ENABLE ON) -set(FP16_ENABLE OFF) +set(CUDNN_ENABLE ON) +set(FP16_ENABLE ON) # Jetson AGX Xavier & TITAN V is under version of Turing. So, please set manually. # Turing or Ampere GPUs, FP16 is automatically enabled. From 43b74a7bbe8ebd2ca4bbfd11dfa96705557f70e5 Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Sun, 5 Dec 2021 13:47:21 +0900 Subject: [PATCH 57/64] add download option --- darknet_ros/CMakeLists.txt | 104 +++++++++++++++++++++++++------------ 1 file changed, 72 insertions(+), 32 deletions(-) diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index bc93a883a..0125cfac3 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -8,8 +8,15 @@ set(CMAKE_CXX_STANDARD 17) # USER SETTINGS ================================================================= set(CUDA_ENABLE ON) -set(CUDNN_ENABLE OFF) # set(CUDNN_ENABLE ON) -set(FP16_ENABLE OFF) +set(CUDNN_ENABLE ON) # set(CUDNN_ENABLE ON) +set(FP16_ENABLE ON) + +set(DOWNLOAD_YOLOV2_TINY ON) +set(DOWNLOAD_YOLOV3 ON) +set(DOWNLOAD_YOLOV4 ON) +set(DOWNLOAD_YOLOV4_CSP OFF) +set(DOWNLOAD_YOLOV4_TINY OFF) +set(DOWNLOAD_YOLOV4_MISH OFF) # Jetson AGX Xavier & TITAN V is under version of Turing. So, please set manually. # Turing or Ampere GPUs, FP16 is automatically enabled. @@ -295,44 +302,77 @@ 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}) -# 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}) -# endif() +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 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}) +# Download yolov3.weights +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 -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 ...") - execute_process(COMMAND wget -q https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v4_pre/yolov4-tiny.weights -P ${PATH}) +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 -# 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() +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://raw.githubusercontent.com/AlexeyAB/darknet/master/cfg/yolov4-csp.cfg -P ${PATH}/../cfg) + 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://raw.githubusercontent.com/AlexeyAB/darknet/master/cfg/yolov4x-mish.cfg -P ${PATH}/../cfg) + 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() install(DIRECTORY yolo_network_config/cfg yolo_network_config/weights DESTINATION share/${PROJECT_NAME}/yolo_network_config/) From 9f5d20b0b3d9278c9b225df2be05bed113e806f9 Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Sun, 5 Dec 2021 18:58:43 +0900 Subject: [PATCH 58/64] add yolov4-csp --- darknet_ros/CMakeLists.txt | 6 +- darknet_ros/config/yolov4-csp.yaml | 91 ++ .../yolo_network_config/cfg/yolov4-csp.cfg | 1280 +++++++++++++++++ 3 files changed, 1374 insertions(+), 3 deletions(-) create mode 100644 darknet_ros/config/yolov4-csp.yaml create mode 100644 darknet_ros/yolo_network_config/cfg/yolov4-csp.cfg diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 0125cfac3..9367680bb 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -14,8 +14,8 @@ set(FP16_ENABLE ON) set(DOWNLOAD_YOLOV2_TINY ON) set(DOWNLOAD_YOLOV3 ON) set(DOWNLOAD_YOLOV4 ON) -set(DOWNLOAD_YOLOV4_CSP OFF) -set(DOWNLOAD_YOLOV4_TINY OFF) +set(DOWNLOAD_YOLOV4_CSP ON) +set(DOWNLOAD_YOLOV4_TINY ON) set(DOWNLOAD_YOLOV4_MISH OFF) # Jetson AGX Xavier & TITAN V is under version of Turing. So, please set manually. @@ -355,7 +355,7 @@ if(DOWNLOAD_YOLOV4_CSP) 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://raw.githubusercontent.com/AlexeyAB/darknet/master/cfg/yolov4-csp.cfg -P ${PATH}/../cfg) + # execute_process(COMMAND wget -q https://raw.githubusercontent.com/AlexeyAB/darknet/master/cfg/yolov4-csp.cfg -P ${PATH}/../cfg) 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.") diff --git a/darknet_ros/config/yolov4-csp.yaml b/darknet_ros/config/yolov4-csp.yaml new file mode 100644 index 000000000..1f7243c19 --- /dev/null +++ b/darknet_ros/config/yolov4-csp.yaml @@ -0,0 +1,91 @@ +darknet_ros: + ros__parameters: + yolo_model: + config_file: + name: yolov4-csp.cfg + weight_file: + name: yolov4-csp.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/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 From 094a73bfa6fa1d1e8c9901a1a390ab38bee727db Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Sun, 5 Dec 2021 18:59:35 +0900 Subject: [PATCH 59/64] update CMakeLists --- darknet_ros/CMakeLists.txt | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 9367680bb..b060cf5c6 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -12,9 +12,9 @@ set(CUDNN_ENABLE ON) # set(CUDNN_ENABLE ON) set(FP16_ENABLE ON) set(DOWNLOAD_YOLOV2_TINY ON) -set(DOWNLOAD_YOLOV3 ON) +set(DOWNLOAD_YOLOV3 OFF) set(DOWNLOAD_YOLOV4 ON) -set(DOWNLOAD_YOLOV4_CSP ON) +set(DOWNLOAD_YOLOV4_CSP OFF) set(DOWNLOAD_YOLOV4_TINY ON) set(DOWNLOAD_YOLOV4_MISH OFF) From e610076e39ffce170699090b2a2051896513769c Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Tue, 26 Apr 2022 18:35:38 +0900 Subject: [PATCH 60/64] cuda11-galactic --- darknet_ros/CMakeLists.txt | 8 +++++--- darknet_ros/launch/darknet_ros.launch.py | 4 ++-- .../launch/{yolov4.launch.py => yolov4-csp.launch.py} | 4 ++-- darknet_ros/launch/yolov4-tiny.launch.py | 2 +- 4 files changed, 10 insertions(+), 8 deletions(-) rename darknet_ros/launch/{yolov4.launch.py => yolov4-csp.launch.py} (88%) diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index b060cf5c6..f86811609 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -13,8 +13,8 @@ set(FP16_ENABLE ON) set(DOWNLOAD_YOLOV2_TINY ON) set(DOWNLOAD_YOLOV3 OFF) -set(DOWNLOAD_YOLOV4 ON) -set(DOWNLOAD_YOLOV4_CSP OFF) +set(DOWNLOAD_YOLOV4 OFF) +set(DOWNLOAD_YOLOV4_CSP ON) set(DOWNLOAD_YOLOV4_TINY ON) set(DOWNLOAD_YOLOV4_MISH OFF) @@ -48,7 +48,9 @@ if (CUDA_FOUND) -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_86,code=[sm_86,compute_86] # GeForce RTX 3000 Series + -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() diff --git a/darknet_ros/launch/darknet_ros.launch.py b/darknet_ros/launch/darknet_ros.launch.py index b2bd6b57f..39a82a69a 100644 --- a/darknet_ros/launch/darknet_ros.launch.py +++ b/darknet_ros/launch/darknet_ros.launch.py @@ -40,8 +40,8 @@ def generate_launch_description(): 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, { diff --git a/darknet_ros/launch/yolov4.launch.py b/darknet_ros/launch/yolov4-csp.launch.py similarity index 88% rename from darknet_ros/launch/yolov4.launch.py rename to darknet_ros/launch/yolov4-csp.launch.py index 0ce6e0bb5..a805cea1c 100644 --- a/darknet_ros/launch/yolov4.launch.py +++ b/darknet_ros/launch/yolov4-csp.launch.py @@ -6,7 +6,7 @@ def generate_launch_description(): darknet_ros_share_dir = get_package_share_directory('darknet_ros') - network_param_file = darknet_ros_share_dir + '/config/yolov4.yaml' + 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']), @@ -15,7 +15,7 @@ def generate_launch_description(): camera = Node( package="v4l2_camera", - node_executable="v4l2_camera_node", + executable="v4l2_camera_node", parameters=[ {'video_device' : "/dev/video0"}, ]) diff --git a/darknet_ros/launch/yolov4-tiny.launch.py b/darknet_ros/launch/yolov4-tiny.launch.py index a321129fb..69a42fdeb 100644 --- a/darknet_ros/launch/yolov4-tiny.launch.py +++ b/darknet_ros/launch/yolov4-tiny.launch.py @@ -15,7 +15,7 @@ def generate_launch_description(): camera = Node( package="v4l2_camera", - node_executable="v4l2_camera_node", + executable="v4l2_camera_node", parameters=[ {'video_device' : "/dev/video0"}, ]) From f53a5e93377d31ff7e35722456afb5753097bcb1 Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Tue, 26 Apr 2022 18:38:03 +0900 Subject: [PATCH 61/64] yolov2-tiny off --- darknet_ros/CMakeLists.txt | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index f86811609..8f8639f74 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -11,7 +11,7 @@ set(CUDA_ENABLE ON) set(CUDNN_ENABLE ON) # set(CUDNN_ENABLE ON) set(FP16_ENABLE ON) -set(DOWNLOAD_YOLOV2_TINY ON) +set(DOWNLOAD_YOLOV2_TINY OFF) set(DOWNLOAD_YOLOV3 OFF) set(DOWNLOAD_YOLOV4 OFF) set(DOWNLOAD_YOLOV4_CSP ON) From 73a2fd3058bbb86c6e757b4630cfceacfa4e8520 Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Sat, 23 Jul 2022 13:45:50 +0900 Subject: [PATCH 62/64] update submodule --- darknet | 2 +- 1 file changed, 1 insertion(+), 1 deletion(-) diff --git a/darknet b/darknet index e2a128737..25505164a 160000 --- a/darknet +++ b/darknet @@ -1 +1 @@ -Subproject commit e2a128737bcee224088a0076629983e2a4beca01 +Subproject commit 25505164a3bd6235c75deaad325878ceda90249a From 57cfad4849792088a97146e08b3ef05aac55ddd6 Mon Sep 17 00:00:00 2001 From: Ar-Ray-code Date: Sat, 23 Jul 2022 14:50:59 +0900 Subject: [PATCH 63/64] add yolov7-tiny --- darknet_ros/CMakeLists.txt | 18 +- darknet_ros/config/yolov7-tiny.yaml | 92 +++ .../darknet_ros/YoloObjectDetector.hpp | 2 + darknet_ros/launch/yolov4-csp.launch.py | 2 +- darknet_ros/launch/yolov7-tiny.launch.py | 27 + darknet_ros/src/YoloObjectDetector.cpp | 13 +- .../yolo_network_config/cfg/yolov7-tiny.cfg | 706 ++++++++++++++++++ rm_darknet_CMakeLists.sh | 3 +- 8 files changed, 852 insertions(+), 11 deletions(-) create mode 100644 darknet_ros/config/yolov7-tiny.yaml create mode 100644 darknet_ros/launch/yolov7-tiny.launch.py create mode 100644 darknet_ros/yolo_network_config/cfg/yolov7-tiny.cfg diff --git a/darknet_ros/CMakeLists.txt b/darknet_ros/CMakeLists.txt index 8f8639f74..43758d444 100644 --- a/darknet_ros/CMakeLists.txt +++ b/darknet_ros/CMakeLists.txt @@ -17,6 +17,7 @@ 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. @@ -184,7 +185,9 @@ set(DARKNET_CORE_FILES ${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/yolo_layer.c ${DARKNET_PATH}/src/representation_layer.c + + ) set(DARKNET_CUDA_FILES @@ -357,7 +360,6 @@ if(DOWNLOAD_YOLOV4_CSP) 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://raw.githubusercontent.com/AlexeyAB/darknet/master/cfg/yolov4-csp.cfg -P ${PATH}/../cfg) 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.") @@ -370,12 +372,20 @@ if(DOWNLOAD_YOLOV4_MISH) 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://raw.githubusercontent.com/AlexeyAB/darknet/master/cfg/yolov4x-mish.cfg -P ${PATH}/../cfg) 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/) install(DIRECTORY launch config DESTINATION share/${PROJECT_NAME}/) @@ -398,7 +408,7 @@ install(DIRECTORY launch config DESTINATION share/${PROJECT_NAME}/) # ament_lint_auto_find_test_dependencies() # find_package(ament_cmake_gtest REQUIRED) - + #ament_add_gtest(${PROJECT_NAME}_object_detection-test # test/object_detection.test # test/test_main.cpp 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 4cb458845..2dcf5c207 100644 --- a/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp +++ b/darknet_ros/include/darknet_ros/YoloObjectDetector.hpp @@ -197,6 +197,8 @@ class YoloObjectDetector : public rclcpp::Node image **demoAlphabet_; int demoClasses_; + std::string windowName_; + network *net_; std_msgs::msg::Header headerBuff_[3]; image buff_[3]; diff --git a/darknet_ros/launch/yolov4-csp.launch.py b/darknet_ros/launch/yolov4-csp.launch.py index a805cea1c..6d5eec347 100644 --- a/darknet_ros/launch/yolov4-csp.launch.py +++ b/darknet_ros/launch/yolov4-csp.launch.py @@ -19,7 +19,7 @@ def generate_launch_description(): parameters=[ {'video_device' : "/dev/video0"}, ]) - + return LaunchDescription([ darknet_ros_launch, # if you want to disable camera node, remove the following line. diff --git a/darknet_ros/launch/yolov7-tiny.launch.py b/darknet_ros/launch/yolov7-tiny.launch.py new file mode 100644 index 000000000..fbb2645ab --- /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, + ]) \ No newline at end of file diff --git a/darknet_ros/src/YoloObjectDetector.cpp b/darknet_ros/src/YoloObjectDetector.cpp index 7bec08e0a..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! @@ -473,7 +476,7 @@ float get_pixel_cp(image m, int x, int y, int c) int windows = 0; void* YoloObjectDetector::displayInThread(void* ptr) { - show_image_cv(buff_[(buffIndex_ + 1) % 3], "YOLO V4"); + show_image_cv(buff_[(buffIndex_ + 1) % 3], windowName_.c_str()); int c = cv::waitKey(waitKeyDelay_); if (c != -1) c = c % 256; if (c == 27) { @@ -594,12 +597,12 @@ void YoloObjectDetector::yolo() int count = 0; if (!demoPrefix_ && viewImage_) { - cv::namedWindow("YOLO V4", cv::WINDOW_NORMAL); + cv::namedWindow(windowName_.c_str(), cv::WINDOW_NORMAL); if (fullScreen_) { - cv::setWindowProperty("YOLO V4", cv::WND_PROP_FULLSCREEN, cv::WINDOW_FULLSCREEN); + cv::setWindowProperty(windowName_.c_str(), cv::WND_PROP_FULLSCREEN, cv::WINDOW_FULLSCREEN); } else { - cv::moveWindow("YOLO V4", 0, 0); - cv::resizeWindow("YOLO V4", 640, 480); + cv::moveWindow(windowName_.c_str(), 0, 0); + cv::resizeWindow(windowName_.c_str(), 640, 480); } } diff --git a/darknet_ros/yolo_network_config/cfg/yolov7-tiny.cfg b/darknet_ros/yolo_network_config/cfg/yolov7-tiny.cfg new file mode 100644 index 000000000..4628b43fc --- /dev/null +++ b/darknet_ros/yolo_network_config/cfg/yolov7-tiny.cfg @@ -0,0 +1,706 @@ +[net] +# Testing +#batch=1 +#subdivisions=1 +# Training +batch=1 +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 + +# 0 +[convolutional] +batch_normalize=1 +filters=32 +size=3 +stride=2 +pad=1 +activation=leaky + +# 1 +[convolutional] +batch_normalize=1 +filters=64 +size=3 +stride=2 +pad=1 +activation=leaky + +[convolutional] +batch_normalize=1 +filters=32 +size=1 +stride=1 +pad=1 +activation=leaky + +[route] +layers=-2 + +[convolutional] +batch_normalize=1 +filters=32 +size=1 +stride=1 +pad=1 +activation=leaky + +[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 = -5,-3,-2,-1 + +# 8 +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=leaky + +[maxpool] +size=2 +stride=2 + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=leaky + +[route] +layers=-2 + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=leaky + +[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 = -5,-3,-2,-1 + +# 16 +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=leaky + +[maxpool] +size=2 +stride=2 + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=leaky + +[route] +layers=-2 + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=leaky + +[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 = -5,-3,-2,-1 + +# 24 +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=leaky + +[maxpool] +size=2 +stride=2 + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=leaky + +[route] +layers=-2 + +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=leaky + +[convolutional] +batch_normalize=1 +filters=256 +size=3 +stride=1 +pad=1 +activation=leaky + +[convolutional] +batch_normalize=1 +filters=256 +size=3 +stride=1 +pad=1 +activation=leaky + +[route] +layers = -5,-3,-2,-1 + +# 32 +[convolutional] +batch_normalize=1 +filters=512 +size=1 +stride=1 +pad=1 +activation=leaky + + +################################## + +### SPPCSP ### +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=leaky + +[route] +layers = -2 + +[convolutional] +batch_normalize=1 +filters=256 +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=256 +size=1 +stride=1 +pad=1 +activation=leaky + +[route] +layers = -10,-1 + +# 44 +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=leaky +### End SPPCSP ### + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=leaky + +[upsample] +stride=2 + +[route] +layers = 24 + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=leaky + +[route] +layers = -1,-3 + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=leaky + +[route] +layers=-2 + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=leaky + +[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 = -5,-3,-2,-1 + +# 56 +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=leaky + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=leaky + +[upsample] +stride=2 + +[route] +layers = 16 + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=leaky + +[route] +layers = -1,-3 + +[convolutional] +batch_normalize=1 +filters=32 +size=1 +stride=1 +pad=1 +activation=leaky + +[route] +layers=-2 + +[convolutional] +batch_normalize=1 +filters=32 +size=1 +stride=1 +pad=1 +activation=leaky + +[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 = -5,-3,-2,-1 + +# 68 +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=leaky + +########################## + +[convolutional] +batch_normalize=1 +size=3 +stride=2 +pad=1 +filters=128 +activation=leaky + +[route] +layers = -1,56 + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=leaky + +[route] +layers=-2 + +[convolutional] +batch_normalize=1 +filters=64 +size=1 +stride=1 +pad=1 +activation=leaky + +[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 = -5,-3,-2,-1 + +# 77 +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=leaky + +[convolutional] +batch_normalize=1 +size=3 +stride=2 +pad=1 +filters=256 +activation=leaky + +[route] +layers = -1,44 + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=leaky + +[route] +layers=-2 + +[convolutional] +batch_normalize=1 +filters=128 +size=1 +stride=1 +pad=1 +activation=leaky + +[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 = -5,-3,-2,-1 + +# 86 +[convolutional] +batch_normalize=1 +filters=256 +size=1 +stride=1 +pad=1 +activation=leaky + +############################# + +# ============ End of Neck ============ # + +# ============ Head ============ # + + +# P3 +[route] +layers = 68 + +[convolutional] +batch_normalize=1 +size=3 +stride=1 +pad=1 +filters=128 +activation=leaky + +[convolutional] +size=1 +stride=1 +pad=1 +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 +size=3 +stride=1 +pad=1 +filters=256 +activation=leaky + +[convolutional] +size=1 +stride=1 +pad=1 +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=512 +activation=leaky + +[convolutional] +size=1 +stride=1 +pad=1 +filters=255 +#activation=linear +activation=logistic + +[yolo] +mask = 6,7,8 +anchors = 10,13, 16,30, 33,23, 30,61, 62,45, 59,119, 116,90, 156,198, 373,326 +classes=80 +num=9 +jitter=.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 diff --git a/rm_darknet_CMakeLists.sh b/rm_darknet_CMakeLists.sh index cda7c8d64..13d9bae80 100755 --- a/rm_darknet_CMakeLists.sh +++ b/rm_darknet_CMakeLists.sh @@ -1,3 +1,4 @@ #!/bin/sh SCRIPT_DIR=$(cd $(dirname $0); pwd) -rm $SCRIPT_DIR/darknet/CMakeLists.txt \ No newline at end of file +rm $SCRIPT_DIR/darknet/CMakeLists.txt +rm $SCRIPT_DIR/darknet/src/csharp/CMakeLists.txt \ No newline at end of file From df79053480df97db0a972d8b2c9beeadb1126e7f Mon Sep 17 00:00:00 2001 From: Ar-Ray <67567093+Ar-Ray-code@users.noreply.github.com> Date: Sat, 23 Jul 2022 16:45:59 +0900 Subject: [PATCH 64/64] Update yolov7-tiny.launch.py --- darknet_ros/launch/yolov7-tiny.launch.py | 4 ++-- 1 file changed, 2 insertions(+), 2 deletions(-) diff --git a/darknet_ros/launch/yolov7-tiny.launch.py b/darknet_ros/launch/yolov7-tiny.launch.py index fbb2645ab..e38bb3e94 100644 --- a/darknet_ros/launch/yolov7-tiny.launch.py +++ b/darknet_ros/launch/yolov7-tiny.launch.py @@ -23,5 +23,5 @@ def generate_launch_description(): return LaunchDescription([ darknet_ros_launch, # if you want to disable camera node, remove the following line. - # camera, - ]) \ No newline at end of file + camera, + ])