Skip to content
New issue

Have a question about this project? Sign up for a free GitHub account to open an issue and contact its maintainers and the community.

By clicking “Sign up for GitHub”, you agree to our terms of service and privacy statement. We’ll occasionally send you account related emails.

Already on GitHub? Sign in to your account

[feature] Initial release of Yolo v3 node #1202

Merged
merged 3 commits into from
Apr 9, 2018
Merged
Show file tree
Hide file tree
Changes from all commits
Commits
File filter

Filter by extension

Filter by extension

Conversations
Failed to load comments.
Loading
Jump to
Jump to file
Failed to load files.
Loading
Diff view
Diff view
Original file line number Diff line number Diff line change
@@ -1,26 +1,21 @@
<launch>
<arg name="car" default="true"/>
<arg name="pedestrian" default="false"/>
<arg name="use_gpu" default="true"/>
<arg name="gpu_device_id" default="0"/>
<arg name="score_threshold" default="0.3"/>

<!-- arguments list -->

<arg name="network_definition_file" default="$(env HOME)/darknet/cfg/yolo.cfg"/>
<arg name="pretrained_model_file" default="$(env HOME)/darknet/data/yolo.weights"/>
<arg name="gpu_device_id" default="0"/>
<arg name="score_threshold" default="0.3"/>
<arg name="nms_threshold" default="0.45"/>

<arg name="network_definition_file" default="$(env HOME)/darknet/cfg/yolo.cfg"/>
<arg name="pretrained_model_file" default="$(env HOME)/darknet/data/yolo.weights"/>

<arg name="camera_id" default="/"/>
<arg name="image_src" default="/image_raw"/>

<node pkg="cv_tracker" name="yolo2_wa" type="yolo2_wa">
<param name="network_definition_file" type="str" value="$(arg network_definition_file)"/>
<param name="pretrained_model_file" type="str" value="$(arg pretrained_model_file)"/>
<param name="score_threshold" type="double" value="$(arg score_threshold)"/>
<param name="nms_threshold" type="double" value="$(arg nms_threshold)"/>
<param name="gpu_device_id" type="int" value="$(arg gpu_device_id)"/>
<param name="image_raw_node" type="str" value="$(arg camera_id)$(arg image_src)"/>
</node>

<arg name="camera_id" default="/" />
<arg name="image_src" default="/image_raw"/>

<!-- SSD -->
<node pkg="cv_tracker" name="yolo2_wa" type="yolo2_wa">
<param name="network_definition_file" type="str" value="$(arg network_definition_file)"/>
<param name="pretrained_model_file" type="str" value="$(arg pretrained_model_file)"/>
<param name="use_gpu" type="bool" value="$(arg use_gpu)" />
<param name="score_threshold" type="double" value="$(arg score_threshold)"/>
<param name="gpu_device_id" type="int" value="$(arg gpu_device_id)"/>
<param name="image_raw_node" type="str" value="$(arg camera_id)$(arg image_src)"/>
</node>

</launch>
Original file line number Diff line number Diff line change
Expand Up @@ -191,7 +191,7 @@ class Yolo2DetectorNode
void image_callback(const sensor_msgs::ImageConstPtr& in_image_message)
{
std::vector< RectClassScore<float> > detections;
//darknet_image = yolo_detector_.convert_image(in_image_message);
//darknet_image_ = yolo_detector_.convert_image(in_image_message);

darknet_image = convert_ipl_to_image(in_image_message);

Expand Down
Original file line number Diff line number Diff line change
@@ -0,0 +1,154 @@
cmake_minimum_required(VERSION 2.8.12)
project(yolo3_detector)

find_package(catkin REQUIRED COMPONENTS
cv_bridge
image_transport
roscpp
sensor_msgs
std_msgs
autoware_msgs
)

find_package(CUDA)
find_package(OpenCV REQUIRED)
find_package(OpenMP)

catkin_package(CATKIN_DEPENDS
cv_bridge
image_transport
roscpp
sensor_msgs
std_msgs
autoware_msgs
)

set(CMAKE_CXX_FLAGS "-std=c++11 -O3 -g -Wall ${CMAKE_CXX_FLAGS}")

IF (CUDA_FOUND)
list(APPEND CUDA_NVCC_FLAGS "--std=c++11 -I$${PROJECT_SOURCE_DIR}/darknet/src -I${PROJECT_SOURCE_DIR}/src -DGPU")
SET(CUDA_PROPAGATE_HOST_FLAGS OFF)

#darknet
cuda_add_library(yolo3_detector_lib SHARED
darknet/src/activation_kernels.cu
darknet/src/avgpool_layer_kernels.cu
darknet/src/convolutional_kernels.cu
darknet/src/crop_layer_kernels.cu
darknet/src/col2im_kernels.cu
darknet/src/blas_kernels.cu
darknet/src/deconvolutional_kernels.cu
darknet/src/dropout_layer_kernels.cu
darknet/src/im2col_kernels.cu
darknet/src/maxpool_layer_kernels.cu

darknet/src/gemm.c
darknet/src/utils.c
darknet/src/cuda.c
darknet/src/deconvolutional_layer.c
darknet/src/convolutional_layer.c
darknet/src/list.c
darknet/src/image.c
darknet/src/activations.c
darknet/src/im2col.c
darknet/src/col2im.c
darknet/src/blas.c
darknet/src/crop_layer.c
darknet/src/dropout_layer.c
darknet/src/maxpool_layer.c
darknet/src/softmax_layer.c
darknet/src/data.c
darknet/src/matrix.c
darknet/src/network.c
darknet/src/connected_layer.c
darknet/src/cost_layer.c
darknet/src/parser.c
darknet/src/option_list.c
darknet/src/detection_layer.c
darknet/src/route_layer.c
darknet/src/upsample_layer.c
darknet/src/box.c
darknet/src/normalization_layer.c
darknet/src/avgpool_layer.c
darknet/src/layer.c
darknet/src/local_layer.c
darknet/src/shortcut_layer.c
darknet/src/logistic_layer.c
darknet/src/activation_layer.c
darknet/src/rnn_layer.c
darknet/src/gru_layer.c
darknet/src/crnn_layer.c
darknet/src/batchnorm_layer.c
darknet/src/region_layer.c
darknet/src/reorg_layer.c
darknet/src/tree.c
darknet/src/lstm_layer.c
darknet/src/l2norm_layer.c
darknet/src/yolo_layer.c
)

target_compile_definitions(yolo3_detector_lib PUBLIC -DGPU)
cuda_add_cublas_to_target(yolo3_detector_lib)

if (OPENMP_FOUND)
set_target_properties(yolo3_detector_lib PROPERTIES
COMPILE_FLAGS ${OpenMP_CXX_FLAGS}
LINK_FLAGS ${OpenMP_CXX_FLAGS}
)
endif ()

target_include_directories(yolo3_detector_lib PRIVATE
${OpenCV_INCLUDE_DIR}
${catkin_INCLUDE_DIRS}
${Boost_INCLUDE_DIRS}
${CUDA_INCLUDE_DIRS}
${PROJECT_SOURCE_DIR}/darknet
${PROJECT_SOURCE_DIR}/darknet/src
${PROJECT_SOURCE_DIR}/src
)

target_link_libraries(yolo3_detector_lib
${OpenCV_LIBRARIES}
${catkin_LIBRARIES}
${PCL_LIBRARIES}
${Qt5Core_LIBRARIES}
${CUDA_LIBRARIES}
${CUDA_CUBLAS_LIBRARIES}
${CUDA_curand_LIBRARY}
)

add_dependencies(yolo3_detector_lib
${catkin_EXPORTED_TARGETS}
)

#ros node
cuda_add_executable(yolo3_detector
src/yolo3_node.cpp
src/yolo3_detector.cpp
src/yolo3_detector.h
)

target_compile_definitions(yolo3_detector PUBLIC -DGPU)

target_include_directories(yolo3_detector PRIVATE
${CUDA_INCLUDE_DIRS}
${catkin_INCLUDE_DIRS}
${PROJECT_SOURCE_DIR}/darknet
${PROJECT_SOURCE_DIR}/darknet/src
${PROJECT_SOURCE_DIR}/src
)

target_link_libraries(yolo3_detector
${catkin_LIBRARIES}
${OpenCV_LIBS}
${CUDA_LIBRARIES}
${CUDA_CUBLAS_LIBRARIES}
${CUDA_curand_LIBRARY}
yolo3_detector_lib
)
add_dependencies(yolo3_detector
${catkin_EXPORTED_TARGETS}
)
ELSE()
message("YOLO3 won't be built, CUDA was not found.")
ENDIF ()
Original file line number Diff line number Diff line change
@@ -0,0 +1,49 @@
# Yolo3 Detector

Autoware package based on Yolov3 image detector.

### Requirements

* NVIDIA GPU with CUDA installed
* Pretrained YOLOv3 model on COCO dataset.

### How to launch

* From a sourced terminal:

`roslaunch yolo3_detector yolo3.launch`

* From Runtime Manager:

Computing Tab -> Detection/ cv_detector -> `yolo3_wa`

### Parameters

Launch file available parameters:

|Parameter| Type| Description|
----------|-----|--------
|`score_threshold`|*Double* |Detections with a confidence value larger than this value will be displayed. Default `0.5`.|
|`nms_threshold`|*Double*|Non-Maximum suppresion area threshold ratio to merge proposals. Default `0.45`.|
|`network_definition_file`|*String*|Network architecture definition configuration file. Default `yolov3.cfg`.|
|`pretrained_model_file`|*String*|Path to pretrained model. Default `yolov3.weights`.|
|`camera_id`|*String*|Camera workspace. Default `/`.|
|`image_src`|*String*|Image source topic. Default `/image_raw`.|

### Subscribed topics

|Topic|Type|Objective|
------|----|---------
|`/image_raw`|`sensor_msgs/Image`|Source image stream to perform detection.|
|`/config/Yolo3`|`autoware_msgs/ConfigSsd`|Configuration adjustment for threshold.|

### Published topics

|Topic|Type|Objective|
------|----|---------
|`/obj_car/image_obj`|`autoware_msgs/image_obj`|Contains the coordinates of the bounding box in image coordinates for objects detected as vehicles.|
|`/obj_person/image_obj`|`autoware_msgs/image_obj`|Contains the coordinates of the bounding box in image coordinates for objects detected as pedestrian.|

### Video

[![Yolo v3 Autoware](https://img.youtube.com/vi/pO4vM4ehI98/0.jpg)](https://www.youtube.com/watch?v=pO4vM4ehI98)
Loading