Skip to content
Snippets Groups Projects
Commit 6ea1eab9 authored by Fernando Herrero's avatar Fernando Herrero
Browse files

Set queue_size and buff_size for image subscriber, to avoid delay

parent f080b751
No related branches found
No related tags found
No related merge requests found
...@@ -243,5 +243,5 @@ def main(args): ...@@ -243,5 +243,5 @@ def main(args):
if __name__ == '__main__': if __name__ == '__main__':
rospy.set_param("use_sim_time", 'true') #rospy.set_param("use_sim_time", 'true')
main(sys.argv) main(sys.argv)
...@@ -76,7 +76,7 @@ class human_detector: ...@@ -76,7 +76,7 @@ class human_detector:
rospy.loginfo(rospy.get_name() + ": " + text) rospy.loginfo(rospy.get_name() + ": " + text)
self.bridge = CvBridge() self.bridge = CvBridge()
self.image_sub = rospy.Subscriber("~camera/color/image_raw", Image, self.callback) self.image_sub = rospy.Subscriber("~camera/color/image_raw", Image, self.callback, queue_size=1, buff_size=6291456)
self.image_pub = rospy.Publisher("~detection_image", Image, queue_size=1) self.image_pub = rospy.Publisher("~detection_image", Image, queue_size=1)
self.bbx_pub = rospy.Publisher("~bounding_box", box_list, queue_size=1) self.bbx_pub = rospy.Publisher("~bounding_box", box_list, queue_size=1)
...@@ -119,26 +119,6 @@ class human_detector: ...@@ -119,26 +119,6 @@ class human_detector:
line_thickness=8, line_thickness=8,
min_score_thresh=0.60) min_score_thresh=0.60)
# Calculate frame time
t1 = time.time()
run_time = t1 - t0
if run_time < 1:
run_time_list.append(run_time)
if len(run_time_list) > 10:
del run_time_list[0]
if len(run_time_list):
avg_run_time = round(sum(run_time_list) / len(run_time_list) * 1000, 1)
left_margin = 10
bottom_margin = 10
time_text_position = (left_margin, data.height-bottom_margin)
cv2.putText(cv_image, 'Run Time: {}ms'.format(avg_run_time),
time_text_position,
font,
font_scale,
font_color,
line_type)
counter = 0 counter = 0
list_length = 0 list_length = 0
bbx_list = box_list() bbx_list = box_list()
...@@ -181,6 +161,30 @@ class human_detector: ...@@ -181,6 +161,30 @@ class human_detector:
self.detection2d_array_pub.publish(det2d_array) self.detection2d_array_pub.publish(det2d_array)
# Calculate frame time
t1 = time.time()
run_time = t1 - t0
#if run_time < 1:
run_time_list.append(run_time)
if len(run_time_list) > 10:
del run_time_list[0]
#else:
#print "run_time>1"
#rospy.logerr("run_time=%f",run_time)
if len(run_time_list):
avg_run_time = round(sum(run_time_list)*1000 / len(run_time_list) , 1)
left_margin = 10
bottom_margin = 10
time_text_position = (left_margin, data.height-bottom_margin)
cv2.putText(cv_image, 'Run Time: {}ms'.format(avg_run_time),
time_text_position,
font,
font_scale,
font_color,
line_type)
try: try:
cvt_msg = self.bridge.cv2_to_imgmsg(cv_image, "bgr8") cvt_msg = self.bridge.cv2_to_imgmsg(cv_image, "bgr8")
cvt_msg.header.stamp = data.header.stamp cvt_msg.header.stamp = data.header.stamp
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment