Skip to content

Commit 9b4eadb

Browse files
Maik Zickermannniliha
authored andcommitted
add option to mediator to allow logging of YOLO's detections
update .gitignore
1 parent 3358e29 commit 9b4eadb

File tree

6 files changed

+33
-15
lines changed

6 files changed

+33
-15
lines changed

.gitignore

Lines changed: 3 additions & 1 deletion
Original file line numberDiff line numberDiff line change
@@ -1,2 +1,4 @@
11
build/
2-
2+
jetson_nano/catkin_ws/src/darknet_ros/darknet/.nvcc-gcc/
3+
jetson_nano/catkin_ws/src/darknet_ros/darknet/libdarknet.a
4+
jetson_nano/catkin_ws/src/darknet_ros/darknet/libdarknet.so

jetson_nano/catkin_ws/src/camera/launch/yolo_mediator.launch

Lines changed: 6 additions & 0 deletions
Original file line numberDiff line numberDiff line change
@@ -2,9 +2,15 @@
22
<arg name="frame_slice" default="right" doc="[left, right] camera for object detection" />
33
<arg name="scale_factor" default="1.0" doc="Factor to scale frame by" />
44
<arg name="calib" default="true" doc="Use calibrated camera frame" />
5+
<arg name="log_detection" default="false" doc="Print YOLO's detections with bounding box to terminal" />
6+
<arg name="thresh" default="0.3" doc="Probability threshold for log_detection in range [0, 1]" />
7+
<arg name="verbose" default="true" doc="Verbose output" />
58
<param name="frame_slice" value="$(arg frame_slice)" type="str" />
69
<param name="scale_factor" value="$(arg scale_factor)" type="double" />
710
<param name="calib" value="$(arg calib)" type="bool" />
11+
<param name="log_detection" value="$(arg log_detection)" type="bool" />
12+
<param name="thresh" value="$(arg thresh)" type="double" />
13+
<param name="verbose" value="$(arg verbose)" type="bool" />
814

915
<node
1016
pkg="camera"

jetson_nano/catkin_ws/src/camera/scripts/camera.py

Whitespace-only changes.

jetson_nano/catkin_ws/src/camera/scripts/camera_pub.py

Lines changed: 2 additions & 2 deletions
Original file line numberDiff line numberDiff line change
@@ -23,8 +23,8 @@ def publish_message():
2323

2424
# Node is publishing to the video_frames topic using
2525
# the message type Image
26-
pub_corr_both = rospy.Publisher('/camera/frame_corr_both', Image, queue_size=3)
27-
pub_both = rospy.Publisher('/camera/frame_both', Image, queue_size=3)
26+
pub_corr_both = rospy.Publisher('/camera/frame_corr_both', Image, queue_size=1)
27+
pub_both = rospy.Publisher('/camera/frame_both', Image, queue_size=1)
2828

2929
# Tells rospy the name of the node.
3030
# Anonymous = True makes sure the node has a unique name. Random

jetson_nano/catkin_ws/src/camera/scripts/yolo_mediator.py

Lines changed: 15 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -3,7 +3,7 @@
33
import rospy
44
from cv_bridge import CvBridge
55
from sensor_msgs.msg import Image
6-
6+
from darknet_ros_msgs.msg import BoundingBoxes, BoundingBox
77

88
class Mediator:
99
def __init__(self, cfg):
@@ -12,15 +12,16 @@ def __init__(self, cfg):
1212
)
1313
self.cfg = cfg
1414
self.br = CvBridge()
15-
for n in ['frame_slice', 'scale_factor', 'calib']:
15+
for n in ['frame_slice', 'scale_factor', 'calib', 'log_detection', 'thresh', 'verbose']:
1616
rospy.loginfo(f'{n}: {self.cfg[n]}')
1717

1818
def mediate(self, data):
1919
frame = self.br.imgmsg_to_cv2(data)
2020
img, encoding = self.transform_frame(frame)
21-
rospy.loginfo(
22-
f'Mediating video frame {frame.shape} to yolo: {img.shape}'
23-
)
21+
if self.cfg['verbose']:
22+
rospy.loginfo(
23+
f'Mediating video frame {frame.shape} to yolo: {img.shape}'
24+
)
2425
self.yolo_pub.publish(self.br.cv2_to_imgmsg(img, encoding=encoding))
2526

2627
def transform_frame(self, frame):
@@ -37,18 +38,26 @@ def transform_frame(self, frame):
3738
)
3839
return fslice, "rgb8"
3940

41+
def log_detection(self, msg):
42+
for box in msg.bounding_boxes:
43+
if box.probability > self.cfg['thresh']:
44+
rospy.loginfo(f'{box.Class:7s}: {box.probability:2.0%} bbox[x:{box.xmin:4d}, y:{box.ymin:4d}, w:{box.xmax-box.xmin:4d}, h:{box.ymax-box.ymin:4d}]')
4045

4146
def run():
4247
rospy.init_node('yolo_mediator_py', log_level=rospy.INFO)
4348

4449
mediator = Mediator({
4550
k: rospy.get_param(k)
46-
for k in ['frame_slice', 'scale_factor', 'calib']
51+
for k in ['frame_slice', 'scale_factor', 'calib', 'log_detection', 'thresh', 'verbose']
4752
})
4853

4954
frame_both_topic = '/camera/frame_corr_both' if rospy.get_param(
5055
'calib') else '/camera/frame_both'
5156
rospy.Subscriber(frame_both_topic, Image, mediator.mediate)
57+
58+
if mediator.cfg['log_detection']:
59+
rospy.Subscriber('/darknet_ros/bounding_boxes', BoundingBoxes, mediator.log_detection)
60+
5261
rospy.spin()
5362

5463

Lines changed: 7 additions & 6 deletions
Original file line numberDiff line numberDiff line change
@@ -1,13 +1,14 @@
11
cd catkin_workspace/src/darknet_ros/darknet_ros/yolo_network_config/weights/
22

33
COCO data set (Yolo v2):
4-
wget http://pjreddie.com/media/files/yolov2.weights
5-
wget http://pjreddie.com/media/files/yolov2-tiny.weights
4+
wget https://pjreddie.com/media/files/yolov2.weights
5+
wget https://pjreddie.com/media/files/yolov2-tiny.weights
66

77
VOC data set (Yolo v2):
8-
wget http://pjreddie.com/media/files/yolov2-voc.weights
9-
wget http://pjreddie.com/media/files/yolov2-tiny-voc.weights
8+
wget https://pjreddie.com/media/files/yolov2-voc.weights
9+
wget https://pjreddie.com/media/files/yolov2-tiny-voc.weights
1010

1111
Yolo v3:
12-
wget http://pjreddie.com/media/files/yolov3.weights
13-
wget http://pjreddie.com/media/files/yolov3-voc.weights
12+
wget https://pjreddie.com/media/files/yolov3.weights
13+
wget https://pjreddie.com/media/files/yolov3-voc.weights
14+
wget https://pjreddie.com/media/files/yolov3-tiny.weights

0 commit comments

Comments
 (0)