Skip to content

Commit e6fc77e

Browse files
authored
Merge pull request #183 from kunaltyagi/id_num
Add numerical ID and launch param for image
2 parents 687d8f9 + b6432e7 commit e6fc77e

File tree

4 files changed

+7
-2
lines changed

4 files changed

+7
-2
lines changed

darknet_ros/launch/darknet_ros.launch

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -3,6 +3,7 @@
33
<launch>
44
<!-- Console launch prefix -->
55
<arg name="launch_prefix" default=""/>
6+
<arg name="image" default="/camera/rgb/image_raw" />
67

78
<!-- Config and weights folder. -->
89
<arg name="yolo_weights_path" default="$(find darknet_ros)/yolo_network_config/weights"/>
@@ -20,6 +21,7 @@
2021
<node pkg="darknet_ros" type="darknet_ros" name="darknet_ros" output="screen" launch-prefix="$(arg launch_prefix)">
2122
<param name="weights_path" value="$(arg yolo_weights_path)" />
2223
<param name="config_path" value="$(arg yolo_config_path)" />
24+
<remap from="camera/rgb/image_raw" to="$(arg image)" />
2325
</node>
2426

2527
<!--<node name="republish" type="republish" pkg="image_transport" output="screen" args="compressed in:=/front_camera/image_raw raw out:=/camera/image_raw" /> -->

darknet_ros/launch/yolo_v3.launch

Lines changed: 2 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -4,11 +4,13 @@
44

55
<!-- Use YOLOv3 -->
66
<arg name="network_param_file" default="$(find darknet_ros)/config/yolov3.yaml"/>
7+
<arg name="image" default="camera/rgb/image_raw" />
78

89

910
<!-- Include main launch file -->
1011
<include file="$(find darknet_ros)/launch/darknet_ros.launch">
1112
<arg name="network_param_file" value="$(arg network_param_file)"/>
13+
<arg name="image" value="$(arg image)" />
1214
</include>
1315

1416
</launch>

darknet_ros/src/YoloObjectDetector.cpp

Lines changed: 1 addition & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -614,6 +614,7 @@ void *YoloObjectDetector::publishInThread()
614614
int ymax = (rosBoxes_[i][j].y + rosBoxes_[i][j].h / 2) * frameHeight_;
615615

616616
boundingBox.Class = classLabels_[i];
617+
boundingBox.id = i;
617618
boundingBox.probability = rosBoxes_[i][j].prob;
618619
boundingBox.xmin = xmin;
619620
boundingBox.ymin = ymin;

darknet_ros_msgs/msg/BoundingBox.msg

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -1,7 +1,7 @@
1-
string Class
21
float64 probability
32
int64 xmin
43
int64 ymin
54
int64 xmax
65
int64 ymax
7-
6+
int16 id
7+
string Class

0 commit comments

Comments
 (0)