Skip to content

Commit

Permalink
Port to Humble (ros2#10)
Browse files Browse the repository at this point in the history
* refactor: Port package to ROS Humble moving to currently maintained Darknet version instead of darknet_vendor

* feat: Add automatic download of Yolo weights and configuration files to CMake list

* feat: Add launch file for object detector node

* feat: Expose remapping of detections topic

* fix: Add handle for on set parameters callback

* feat: Add automated download of Yolo V3, V4, V4-tiny and V7, default to V7-tiny in detector launch file

* fix: Apply changes to CMake list and configuration files as requested in pull request

* docs: Update read-me
  • Loading branch information
2b-t authored Dec 15, 2023
1 parent be4fd04 commit 45c370a
Show file tree
Hide file tree
Showing 17 changed files with 291 additions and 42 deletions.
12 changes: 12 additions & 0 deletions .gitignore
Original file line number Diff line number Diff line change
@@ -0,0 +1,12 @@
config/yolo-v3/*
!config/yolo-v3/params.yaml
config/yolo-v3-tiny/*
!config/yolo-v3-tiny/params.yaml
config/yolo-v4/*
!config/yolo-v4/params.yaml
config/yolo-v4-tiny/*
!config/yolo-v4-tiny/params.yaml
config/yolo-v7/*
!config/yolo-v7/params.yaml
config/yolo-v7-tiny/*
!config/yolo-v7-tiny/params.yaml
15 changes: 13 additions & 2 deletions CMakeLists.txt
Original file line number Diff line number Diff line change
@@ -1,6 +1,8 @@
cmake_minimum_required(VERSION 3.10)
project(openrobotics_darknet_ros)

option(DOWNLOAD_YOLO_CONFIG "Download YOLO configuration files" OFF)

# Default to C++14
if(NOT CMAKE_CXX_STANDARD)
set(CMAKE_CXX_STANDARD 14)
Expand All @@ -12,7 +14,7 @@ endif()

find_package(ament_cmake REQUIRED)
find_package(cv_bridge REQUIRED)
find_package(darknet_vendor REQUIRED)
find_package(Darknet REQUIRED)
find_package(rclcpp REQUIRED)
find_package(rclcpp_components REQUIRED)
find_package(sensor_msgs REQUIRED)
Expand All @@ -25,9 +27,11 @@ target_include_directories(openrobotics_darknet_ros PUBLIC include)
target_compile_definitions(openrobotics_darknet_ros PRIVATE "DARKNET_ROS_BUILDING_DLL")
ament_target_dependencies(openrobotics_darknet_ros
cv_bridge
darknet_vendor
sensor_msgs
vision_msgs)
target_link_libraries(openrobotics_darknet_ros Darknet::dark)
# Necessary as Darknet currently does not install to ./install/darknet/libdarknet.so
set_target_properties(openrobotics_darknet_ros PROPERTIES INSTALL_RPATH_USE_LINK_PATH TRUE)

add_library(detector_node SHARED
src/detector_node.cpp)
Expand Down Expand Up @@ -70,6 +74,13 @@ install(TARGETS detector_node
install(TARGETS detector_node_main
DESTINATION lib/${PROJECT_NAME})

# Download weights for Yolo v3, v4 and v7
if (DOWNLOAD_YOLO_CONFIG)
include(ConfigDownload.cmake)
endif()

install(DIRECTORY config/ launch/ DESTINATION share/${PROJECT_NAME})
install(DIRECTORY config/ DESTINATION share/${PROJECT_NAME}/config)
install(DIRECTORY include/ DESTINATION include)

ament_package()
105 changes: 105 additions & 0 deletions ConfigDownload.cmake
Original file line number Diff line number Diff line change
@@ -0,0 +1,105 @@
# Download weights for Yolo v3, v4 and v7

# Yolo v3
# See https://pjreddie.com/darknet/yolo/
file(DOWNLOAD
https://raw.githubusercontent.com/pjreddie/darknet/master/data/coco.names
${CMAKE_CURRENT_BINARY_DIR}/config/yolo-v3/coco.names
SHOW_PROGRESS
)
file(DOWNLOAD
https://github.com/AlexeyAB/darknet/blob/master/cfg/yolov3.cfg
${CMAKE_CURRENT_BINARY_DIR}/config/yolo-v3/yolov3.cfg
SHOW_PROGRESS
)
file(DOWNLOAD
https://pjreddie.com/media/files/yolov3.weights
${CMAKE_CURRENT_BINARY_DIR}/config/yolo-v3/yolov3.weights
SHOW_PROGRESS
)
# Yolo v3 tiny
file(DOWNLOAD
https://raw.githubusercontent.com/pjreddie/darknet/master/data/coco.names
${CMAKE_CURRENT_BINARY_DIR}/config/yolo-v3-tiny/coco.names
SHOW_PROGRESS
)
file(DOWNLOAD
https://raw.githubusercontent.com/pjreddie/darknet/master/cfg/yolov3-tiny.cfg
${CMAKE_CURRENT_BINARY_DIR}/config/yolo-v3-tiny/yolov3-tiny.cfg
SHOW_PROGRESS
)
file(DOWNLOAD
https://pjreddie.com/media/files/yolov3-tiny.weights
${CMAKE_CURRENT_BINARY_DIR}/config/yolo-v3-tiny/yolov3-tiny.weights
SHOW_PROGRESS
)

# Yolo v4
# See https://github.com/AlexeyAB/darknet#pre-trained-models
file(DOWNLOAD
https://raw.githubusercontent.com/pjreddie/darknet/master/data/coco.names
${CMAKE_CURRENT_BINARY_DIR}/config/yolo-v4/coco.names
SHOW_PROGRESS
)
file(DOWNLOAD
https://raw.githubusercontent.com/AlexeyAB/darknet/master/cfg/yolov4.cfg
${CMAKE_CURRENT_BINARY_DIR}/config/yolo-v4/yolov4.cfg
SHOW_PROGRESS
)
file(DOWNLOAD
https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v3_optimal/yolov4.weights
${CMAKE_CURRENT_BINARY_DIR}/config/yolo-v4/yolov4.weights
SHOW_PROGRESS
)
# Yolo v4 tiny
file(DOWNLOAD
https://raw.githubusercontent.com/pjreddie/darknet/master/data/coco.names
${CMAKE_CURRENT_BINARY_DIR}/config/yolo-v4-tiny/coco.names
SHOW_PROGRESS
)
file(DOWNLOAD
https://raw.githubusercontent.com/AlexeyAB/darknet/master/cfg/yolov4-tiny.cfg
${CMAKE_CURRENT_BINARY_DIR}/config/yolo-v4-tiny/yolov4-tiny.cfg
SHOW_PROGRESS
)
file(DOWNLOAD
https://github.com/AlexeyAB/darknet/releases/download/darknet_yolo_v4_pre/yolov4-tiny.weights
${CMAKE_CURRENT_BINARY_DIR}/config/yolo-v4-tiny/yolov4-tiny.weights
SHOW_PROGRESS
)

# Yolo v7
# See https://github.com/AlexeyAB/darknet/issues/8595
file(DOWNLOAD
https://raw.githubusercontent.com/pjreddie/darknet/master/data/coco.names
${CMAKE_CURRENT_BINARY_DIR}/config/yolo-v7/coco.names
SHOW_PROGRESS
)
file(DOWNLOAD
https://raw.githubusercontent.com/AlexeyAB/darknet/master/cfg/yolov7.cfg
${CMAKE_CURRENT_BINARY_DIR}/config/yolo-v7/yolov7.cfg
SHOW_PROGRESS
)
file(DOWNLOAD
https://github.com/AlexeyAB/darknet/releases/download/yolov4/yolov7.weights
${CMAKE_CURRENT_BINARY_DIR}/config/yolo-v7/yolov7.weights
SHOW_PROGRESS
)
# Yolo v7 tiny
file(DOWNLOAD
https://raw.githubusercontent.com/pjreddie/darknet/master/data/coco.names
${CMAKE_CURRENT_BINARY_DIR}/config/yolo-v7-tiny/coco.names
SHOW_PROGRESS
)
file(DOWNLOAD
https://raw.githubusercontent.com/AlexeyAB/darknet/master/cfg/yolov7-tiny.cfg
${CMAKE_CURRENT_BINARY_DIR}/config/yolo-v7-tiny/yolov7-tiny.cfg
SHOW_PROGRESS
)
file(DOWNLOAD
https://github.com/AlexeyAB/darknet/releases/download/yolov4/yolov7-tiny.weights
${CMAKE_CURRENT_BINARY_DIR}/config/yolo-v7-tiny/yolov7-tiny.weights
SHOW_PROGRESS
)

install(DIRECTORY ${CMAKE_CURRENT_BINARY_DIR}/config/ DESTINATION share/${PROJECT_NAME}/config/)
46 changes: 31 additions & 15 deletions README.md
Original file line number Diff line number Diff line change
@@ -1,12 +1,12 @@
# Open Robotics Darknet ROS

This is a ROS 2 wrapper around [darknet](https://pjreddie.com/darknet), an open source neural network framework.
This is a **ROS 2 wrapper around [darknet](https://pjreddie.com/darknet)**, an open source neural network framework.

![Example image with bounding boxes created using darknet and the yolov3-tiny network](doc/example_darknet_yolov3-tiny.png)

## DetectorNode

This node can run object detectors like [YOLOv3](https://pjreddie.com/darknet/yolo/) on images.
This node can run **object detectors** like [YOLO v3](https://pjreddie.com/darknet/yolo/) or [YOLO v7](https://github.com/WongKinYiu/yolov7) on images and video streams.

### Subscribers

Expand All @@ -24,35 +24,51 @@ This node can run object detectors like [YOLOv3](https://pjreddie.com/darknet/yo
* `detection.threshold` - Minimum probability of a detection to be published
* `detection.nms_threshold` - Non-maximal Suppression threshold - controls filtering of overlapping boxes

### Example
## Dependencies

Download `YOLOv3-tiny`.
This package depends on [darknet](https://github.com/AlexeyAB/darknet). If you can't use CUDA but want to use your CPU instead make sure to build it with the flag `-DENABLE_CUDA=OFF` and potentially also disabling multi-threading with `-DCMAKE_DISABLE_FIND_PACKAGE_OpenMP=TRUE`.

### Launching

Compiling this package with

```bash
$ colcon build --cmake-args -DDOWNLOAD_YOLO_CONFIG=ON
```
wget https://raw.githubusercontent.com/pjreddie/darknet/f86901f6177dfc6116360a13cc06ab680e0c86b0/cfg/yolov3-tiny.cfg
wget https://pjreddie.com/media/files/yolov3-tiny.weights
wget https://raw.githubusercontent.com/pjreddie/darknet/c6afc7ff1499fbbe64069e1843d7929bd7ae2eaa/data/coco.names

will automatically download the pretrained YOLO v3, v4 and v7 configuration files.

You can then launch the detector node with

```bash
$ ros2 launch openrobotics_darknet_ros detector_launch.py rgb_image:=/topic
```

Save the following as `detector_node_params.yaml`
optionally supplying a desired parameter file `detector_parameters:=path/to/detector_node_params.yaml`.

You can also train YOLO to detect custom objects like described [here](https://github.com/AlexeyAB/darknet#how-to-train-tiny-yolo-to-detect-your-custom-objects) and create the following as `detector_node_params.yaml`:

```yaml
/**:
ros__parameters:
network:
config: "./yolov3-tiny.cfg"
weights: "./yolov3-tiny.weights"
class_names: "./coco.names"
config: "./your-yolo-config.cfg"
weights: "./your-yolo-weights.weights"
class_names: "./your-cocos.names"
detection:
threshold: 0.25
nms_threshold: 0.45
```
Then run the node.
Finally you can run the detector node with
```bash
$ ros2 run openrobotics_darknet_ros detector_node --ros-args --params-file path/to/detector_node_params.yaml
```
ros2 run openrobotics_darknet_ros detector_node __params:=detector_node_params.yaml

and publish images on `~/images` to get the node to detect objects. You can also manually remap an external topic to the `~/images` topic with:

```bash
$ ros2 run openrobotics_darknet_ros detector_node --ros-args --params-file path/to/detector_node_params.yaml -r '~/images:=/your/camera/topic'
```

The node is now running.
Publish images on `~/images` to get the node to detect objects.
9 changes: 9 additions & 0 deletions config/yolo-v3-tiny/params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
/**:
ros__parameters:
network:
config: "$(find-pkg-share openrobotics_darknet_ros)/config/yolo-v3-tiny/yolov3-tiny.cfg"
weights: "$(find-pkg-share openrobotics_darknet_ros)/config/yolo-v3-tiny/yolov3-tiny.weights"
class_names: "$(find-pkg-share openrobotics_darknet_ros)/config/yolo-v3-tiny/coco.names"
detection:
threshold: 0.25
nms_threshold: 0.45
9 changes: 9 additions & 0 deletions config/yolo-v3/params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
/**:
ros__parameters:
network:
config: "$(find-pkg-share openrobotics_darknet_ros)/config/yolo-v3/yolov3.cfg"
weights: "$(find-pkg-share openrobotics_darknet_ros)/config/yolo-v3/yolov3.weights"
class_names: "$(find-pkg-share openrobotics_darknet_ros)/config/yolo-v3/coco.names"
detection:
threshold: 0.25
nms_threshold: 0.45
9 changes: 9 additions & 0 deletions config/yolo-v4-tiny/params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
/**:
ros__parameters:
network:
config: "$(find-pkg-share openrobotics_darknet_ros)/config/yolo-v4-tiny/yolov4-tiny.cfg"
weights: "$(find-pkg-share openrobotics_darknet_ros)/config/yolo-v4-tiny/yolov4-tiny.weights"
class_names: "$(find-pkg-share openrobotics_darknet_ros)/config/yolo-v4-tiny/coco.names"
detection:
threshold: 0.25
nms_threshold: 0.45
9 changes: 9 additions & 0 deletions config/yolo-v4/params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
/**:
ros__parameters:
network:
config: "$(find-pkg-share openrobotics_darknet_ros)/config/yolo-v4/yolov4.cfg"
weights: "$(find-pkg-share openrobotics_darknet_ros)/config/yolo-v4/yolov4.weights"
class_names: "$(find-pkg-share openrobotics_darknet_ros)/config/yolo-v4/coco.names"
detection:
threshold: 0.25
nms_threshold: 0.45
9 changes: 9 additions & 0 deletions config/yolo-v7-tiny/params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
/**:
ros__parameters:
network:
config: "$(find-pkg-share openrobotics_darknet_ros)/config/yolo-v7-tiny/yolov7-tiny.cfg"
weights: "$(find-pkg-share openrobotics_darknet_ros)/config/yolo-v7-tiny/yolov7-tiny.weights"
class_names: "$(find-pkg-share openrobotics_darknet_ros)/config/yolo-v7-tiny/coco.names"
detection:
threshold: 0.25
nms_threshold: 0.45
9 changes: 9 additions & 0 deletions config/yolo-v7/params.yaml
Original file line number Diff line number Diff line change
@@ -0,0 +1,9 @@
/**:
ros__parameters:
network:
config: "$(find-pkg-share openrobotics_darknet_ros)/config/yolo-v7/yolov7.cfg"
weights: "$(find-pkg-share openrobotics_darknet_ros)/config/yolo-v7/yolov7.weights"
class_names: "$(find-pkg-share openrobotics_darknet_ros)/config/yolo-v7/coco.names"
detection:
threshold: 0.25
nms_threshold: 0.45
2 changes: 2 additions & 0 deletions include/openrobotics_darknet_ros/detector_node.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -19,6 +19,7 @@
#include <string>

#include "rclcpp/node.hpp"
#include "rclcpp/node_interfaces/node_parameters_interface.hpp"
#include "openrobotics_darknet_ros/visibility_node.hpp"


Expand All @@ -41,6 +42,7 @@ class DetectorNode : public rclcpp::Node

private:
std::unique_ptr<DetectorNodePrivate> impl_;
rclcpp::node_interfaces::OnSetParametersCallbackHandle::SharedPtr param_callback_handle_;
};
} // namespace darknet_ros
} // namespace openrobotics
Expand Down
52 changes: 52 additions & 0 deletions launch/detector_launch.py
Original file line number Diff line number Diff line change
@@ -0,0 +1,52 @@
import os

from ament_index_python.packages import get_package_share_directory
from launch import LaunchDescription
from launch.actions import DeclareLaunchArgument
from launch.substitutions import LaunchConfiguration
from launch_ros.actions import Node
from launch_ros.parameter_descriptions import ParameterFile


def generate_launch_description():
detector_parameters_file = LaunchConfiguration('detector_parameters')
rgb_image_topic = LaunchConfiguration('rgb_image')
detections_topic = LaunchConfiguration('detections')

default_detector_parameter_file = os.path.join(
get_package_share_directory('openrobotics_darknet_ros'),
'yolo-v7-tiny',
'params.yaml'
)
detector_parameters_cmd = DeclareLaunchArgument(
'detector_parameters',
default_value=default_detector_parameter_file,
description='YOLO object detection configuration file'
)
rgb_image_cmd = DeclareLaunchArgument(
'rgb_image',
description='RGB image that should be used for object detection with YOLO'
)
detections_topic_cmd = DeclareLaunchArgument(
'detections',
default_value='~/detections',
description='Detections containing the bounding boxes of objects to be considered'
)

yolo_detector_node = Node(
package='openrobotics_darknet_ros',
executable='detector_node',
name='detector_node',
remappings=[
('~/images', rgb_image_topic),
('~/detections', detections_topic)
],
parameters = [ParameterFile(detector_parameters_file, allow_substs=True)]
)

ld = LaunchDescription()
ld.add_action(detector_parameters_cmd)
ld.add_action(rgb_image_cmd)
ld.add_action(detections_topic_cmd)
ld.add_action(yolo_detector_node)
return ld
2 changes: 1 addition & 1 deletion package.xml
Original file line number Diff line number Diff line change
Expand Up @@ -12,7 +12,7 @@
<buildtool_depend>ament_cmake</buildtool_depend>

<depend>cv_bridge</depend>
<depend>darknet_vendor</depend>
<depend>darknet</depend>
<depend>rclcpp</depend>
<depend>rclcpp_components</depend>
<depend>sensor_msgs</depend>
Expand Down
2 changes: 1 addition & 1 deletion src/darknet_detections.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef DARKNET_DETECTIONS_HPP_
#define DARKNET_DETECTIONS_HPP_

#include <darknet_vendor/darknet_vendor.h>
#include <darknet.h>

namespace openrobotics
{
Expand Down
2 changes: 1 addition & 1 deletion src/darknet_image.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -15,7 +15,7 @@
#ifndef DARKNET_IMAGE_HPP_
#define DARKNET_IMAGE_HPP_

#include <darknet_vendor/darknet_vendor.h>
#include <darknet.h>
#include <cv_bridge/cv_bridge.h>

#include <memory>
Expand Down
Loading

0 comments on commit 45c370a

Please sign in to comment.