ros / ros_comm

ROS communications-related packages, including core client libraries (roscpp, rospy, roslisp) and graph introspection tools (rostopic, rosnode, rosservice, rosparam).
http://wiki.ros.org/ros_comm
752 stars 913 forks source link

message_filters.ApproximateTimeSynchronizer got stuck after few more runs #2052

Open YunchuZhang opened 3 years ago

YunchuZhang commented 3 years ago

Hi there, I tried to subscribe 2 cameras' topic and show them together(camera1 's rgb, cameara2's depth).But sometimes it can not go into callback function. If I change to subscribe same camera's topic and show them, then it works. Could you help me solve this? Here is my code, I use TimeSynchronizer before, but it does not work, and currently I use ApproximateTimeSynchronizer to make them filtered, but they get stuck after few more runs:

import rospy
import message_filters
from sensor_msgs.msg import Image, CameraInfo
from cv_bridge import CvBridge, CvBridgeError
import cv2
import numpy as np

class LoadImage(object):

def __init__(self):
    self.rcgb1_image = None
    self.depth1_image = None
    self.rgb1_image_sub = message_filters.Subscriber("/camera1/color/image_raw",Image)
    self.depth1_image_sub = message_filters.Subscriber("/camera2/aligned_depth_to_color/image_raw",Image) 
    self.test = message_filters.Subscriber("/camera1/depth/camera_info",CameraInfo) 

    self.bridge_object = CvBridge()
    self.ts = message_filters.ApproximateTimeSynchronizer([self.rgb1_image_sub, self.depth1_image_sub, self.test], 10, 0.1)
    self.ts.registerCallback(self.fusion)
def fusion(self, rgb1, depth1, test):
    rospy.loginfo(test)
    rospy.loginfo("This message will print only once")

    try:
        # We select bgr8 because its the OpenCV encoding by default
        self.rgb1_image = self.bridge_object.imgmsg_to_cv2(rgb1, desired_encoding="bgr8")
    except CvBridgeError as e:
        print(e)
    try:
        # We select 32FC1 because its the OpenCV encoding by default
        self.depth1_image = self.bridge_object.imgmsg_to_cv2(depth1, desired_encoding="32FC1")
    except CvBridgeError as e:
        print(e)
    if self.depth1_image is not None and self.rgb1_image is not None :

        cv2.imshow('rgb1_image',self.rgb1_image)
        # cv2.waitKey(1)
        cv2.imshow('depth1_image',self.depth1_image)
        cv2.waitKey(1)
def main():
    rospy.init_node('load_image_node', anonymous=True)
    rospy.loginfo("Starting load_image_node node")
    load_image_object = LoadImage()
    rospy.sleep(.1)
    try:
        rospy.spin()
    except KeyboardInterrupt:
        print("Shutting down")
    cv2.destroyAllWindows()

if __name__ == '__main__':
    main()

Is that the problem with cv show? The callback function could not be too long? But why it works with same camera's depth and rgb

zaindroid commented 2 years ago

I am having the same issue, have you found any solution so far?

YunchuZhang commented 2 years ago

I still had the same issue sometime.

On Mon, Sep 5, 2022 at 2:43 AM Zain ul Haq @.***> wrote:

I am having the same issue, have you found any solution so far?

— Reply to this email directly, view it on GitHub https://github.com/ros/ros_comm/issues/2052#issuecomment-1236775167, or unsubscribe https://github.com/notifications/unsubscribe-auth/AIAVGNPMXSC7XAZUXLJRVJTV4W6FHANCNFSM4RWURRMA . You are receiving this because you authored the thread.Message ID: @.***>

im-renpei commented 1 year ago

Is there any update to this question? I am having the same issue.

julled commented 1 year ago

I am also having this problem, any updates on this?

ok-kewei commented 4 months ago

increase the message_queue. Here is the line that solved the issue. I increased the queue size from 20 to 1000. It depends on the bandwidth of the topics.
ats = message_filters.ApproximateTimeSynchronizer([lidar_sub, stamped_camera_sub, camera_info, bounding_box], queue_size=1000, slop=800, allow_headerless=True)