leggedrobotics / darknet_ros

YOLO ROS: Real-Time Object Detection for ROS
BSD 3-Clause "New" or "Revised" License
2.22k stars 1.18k forks source link

Sync boundingboxes with images #104

Open mengyuest opened 6 years ago

mengyuest commented 6 years ago

Hi. I am trying to sync boundingboxes with images and I am using message filter to do that. Before that I also modified the header of bbx using _imageHeader. Then I found out the message doesn't coordinate to each other between bbx and images. I used an image publisher working at 0.2Hz and it publishes two pictures in turns. I used rostopic echo /darknet_ros/bounding_boxes to check the message and got the output below.(Followed with an analysis of this sequence)

header: 
  seq: 57526
  stamp: 
    secs: 1532613366
    nsecs:  48888444
  frame_id: "detection"
image_header: 
  seq: 30
  stamp: 
    secs: 1532613366
    nsecs:  48888444
  frame_id: ''
bounding_boxes: 
  - 
    Class: "sheep"
    probability: 0.986069023609
    xmin: 148
    ymin: 34
    xmax: 251
    ymax: 218
  - 
    Class: "sheep"
    probability: 0.98369383812
    xmin: 75
    ymin: 56
    xmax: 154
    ymax: 230
  - 
    Class: "sheep"
    probability: 0.92605394125
    xmin: 95
    ymin: 4
    xmax: 162
    ymax: 83
  - 
    Class: "sheep"
    probability: 0.719430565834
    xmin: 2
    ymin: 75
    xmax: 88
    ymax: 256
  - 
    Class: "sheep"
    probability: 0.55137616396
    xmin: 0
    ymin: 0
    xmax: 33
    ymax: 74
  - 
    Class: "sheep"
    probability: 0.543074071407
    xmin: 154
    ymin: 29
    xmax: 249
    ymax: 115
  - 
    Class: "sheep"
    probability: 0.569041490555
    xmin: 113
    ymin: 0
    xmax: 154
    ymax: 15
---
header: 
  seq: 57527
  stamp: 
    secs: 1532613371
    nsecs:  51276922
  frame_id: "detection"
image_header: 
  seq: 31
  stamp: 
    secs: 1532613371
    nsecs:  51276922
  frame_id: ''
bounding_boxes: 
  - 
    Class: "sheep"
    probability: 0.986069023609
    xmin: 148
    ymin: 34
    xmax: 251
    ymax: 218
  - 
    Class: "sheep"
    probability: 0.98369383812
    xmin: 75
    ymin: 56
    xmax: 154
    ymax: 230
  - 
    Class: "sheep"
    probability: 0.92605394125
    xmin: 95
    ymin: 4
    xmax: 162
    ymax: 83
  - 
    Class: "sheep"
    probability: 0.719430565834
    xmin: 2
    ymin: 75
    xmax: 88
    ymax: 256
  - 
    Class: "sheep"
    probability: 0.55137616396
    xmin: 0
    ymin: 0
    xmax: 33
    ymax: 74
  - 
    Class: "sheep"
    probability: 0.543074071407
    xmin: 154
    ymin: 29
    xmax: 249
    ymax: 115
  - 
    Class: "sheep"
    probability: 0.569041490555
    xmin: 113
    ymin: 0
    xmax: 154
    ymax: 15
---
header: 
  seq: 57528
  stamp: 
    secs: 1532613371
    nsecs:  51276922
  frame_id: "detection"
image_header: 
  seq: 31
  stamp: 
    secs: 1532613371
    nsecs:  51276922
  frame_id: ''
bounding_boxes: 
  - 
    Class: "sheep"
    probability: 0.986069023609
    xmin: 148
    ymin: 34
    xmax: 251
    ymax: 218
  - 
    Class: "sheep"
    probability: 0.98369383812
    xmin: 75
    ymin: 56
    xmax: 154
    ymax: 230
  - 
    Class: "sheep"
    probability: 0.92605394125
    xmin: 95
    ymin: 4
    xmax: 162
    ymax: 83
  - 
    Class: "sheep"
    probability: 0.719430565834
    xmin: 2
    ymin: 75
    xmax: 88
    ymax: 256
  - 
    Class: "sheep"
    probability: 0.55137616396
    xmin: 0
    ymin: 0
    xmax: 33
    ymax: 74
  - 
    Class: "sheep"
    probability: 0.543074071407
    xmin: 154
    ymin: 29
    xmax: 249
    ymax: 115
  - 
    Class: "sheep"
    probability: 0.569041490555
    xmin: 113
    ymin: 0
    xmax: 154
    ymax: 15
---
header: 
  seq: 57529
  stamp: 
    secs: 1532613371
    nsecs:  51276922
  frame_id: "detection"
image_header: 
  seq: 31
  stamp: 
    secs: 1532613371
    nsecs:  51276922
  frame_id: ''
bounding_boxes: 
  - 
    Class: "bicycle"
    probability: 0.573687434196
    xmin: 211
    ymin: 86
    xmax: 253
    ymax: 118
  - 
    Class: "car"
    probability: 0.889243423939
    xmin: 18
    ymin: 57
    xmax: 252
    ymax: 200
---
header: 
  seq: 57530
  stamp: 
    secs: 1532613371
    nsecs:  51276922
  frame_id: "detection"
image_header: 
  seq: 31
  stamp: 
    secs: 1532613371
    nsecs:  51276922
  frame_id: ''
bounding_boxes: 
  - 
    Class: "bicycle"
    probability: 0.573687434196
    xmin: 211
    ymin: 86
    xmax: 253
    ymax: 118
  - 
    Class: "car"
    probability: 0.889243423939
    xmin: 18
    ymin: 57
    xmax: 252
    ymax: 200

Actually there are only two timestamps "1532613366.48888444" and "1532613371.51276922" with five frames("sheep*7", "sheep*7", "sheep*7", "bicycle, car", "bicycle, car"), as the node keeps publishing bbxs at some other frequency. The first timestamp corresponds with an image with sheep, whereas the second timestamp is about cars. In the middle of the sequence there are two frames (57527,57528) that the bbxs have the timestamp with "1532613371.51276922" but detecting "sheep", which can be seen as a wrong correspondency between image and bbx. I wonder why that will happen, and are there any ways to fix that? Thanks.

If any help, here is my image_publisher code.

#!/usr/bin/env python3
from __future__ import print_function

import roslib
import sys
import rospy
import cv2
import std_msgs.msg
from std_msgs.msg import String
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError

# load executable path
# referenced from https://answers.ros.org/question/236116/how-do-i-access-files-in-same-directory-as-executable-python-catkin/
import os, rospkg
rp = rospkg.RosPack()
pwd = rp.get_path("img_publisher")+"/"

def talker():
    bridge=CvBridge()
    pub = rospy.Publisher('image_src', Image, queue_size=10)
    rospy.init_node('talker',anonymous=True)
    rate = rospy.Rate(hz)
    i=0
    predefined_width=256
    predefined_height=256
    while not rospy.is_shutdown():
        i=(i+1)%2
        img=cv2.imread(pwd+"imgs/%d.jpg"%(i))
        img=cv2.resize(img,(predefined_width,predefined_height),interpolation=cv2.INTER_CUBIC)
        ros_img=bridge.cv2_to_imgmsg(img,"bgr8")
        h = std_msgs.msg.Header()
        h.stamp=rospy.Time.now()
        rospy.loginfo("print img at %d. %d"%(h.stamp.secs,h.stamp.nsecs))
        ros_img.header=h
        pub.publish(ros_img)
        rate.sleep()

if __name__ == '__main__':
    try:
        hz=0.2
        talker()
    except rospy.ROSInterruptException:
        pass
rpfly3 commented 6 years ago

@mengyuest Do you solve the problem or has any clue about this problem? I have the same issue here.

mengyuest commented 6 years ago

Yes, though tough for me at first. Notice that they have three buffers to handle things(cache image, detection and publishing) in different stages (like in a pipeline, for raising the throughput I guess). So you need to fetch data in correct index, or will in wrong order. My solution is to also set buffers for headers. When receiving an image, save its header to the corresponding index(same as the index of image buffers) of header buffers, and finally when publishing messages, extract the corresponding header from header buffers. Or you can try to remove all the threads and handle things in one strict sequence as an image callback function (I tried, but got efficiency lost).

rpfly3 commented 6 years ago

@mengyuest Thanks a lot. Will work on it later. BTW: is it possible for you to share your darknet ros package?

umer936 commented 6 years ago

@mengyuest @rpfly3 Hi. Potentially fixed. Only tested on my setup. Would appreciate other people testing it.

PR here: https://github.com/leggedrobotics/darknet_ros/pull/113 Branch for testing here: https://github.com/Texas-Aerial-Robotics/darknet_ros/tree/headerFixForUpsteam

rpfly3 commented 6 years ago

@umer936 Thanks a lot. Will checkout

cuevhv commented 5 years ago

You can always change the header that is being published in darknetros/src/YoloObjectDetector.cpp line 622. This might do the work: boundingBoxesResults.imageheader = headerBuff[(buffIndex + 1) % 3]; //boundingBoxesResults.header.stamp = ros::Time::now(); //line replaced by the next one boundingBoxesResults.header.stamp = boundingBoxesResults.image_header.stamp;