ROS Resources: Documentation | Support | Discussion Forum | Index | Service Status | ros @ Robotics Stack Exchange
Ask Your Question
0

How to subcribe 2 image topics with 1 node in same time ?

asked 2019-01-08 03:04:39 -0500

ToanJunifer gravatar image

Hi buddy,

My name is Toan. I am a newbie in ROS. Now, i'm using Kinect Camera and trying to subcribe 2 image topics with 1 node. But seem like my code is wrong something. If i try to subcribe 1 node with 1 topic is fine. In details, i make case 1 or case 2 is comment , it's work for 1 node 1 topic.

What should i do now ?

This is my code:

#!/usr/bin/env python
import sys
import rospy
import numpy as np
import math
from std_msgs.msg import String
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError
import cv2
#------Start of Class
class image_converter:
    def __init__(self):
        self.bridge = CvBridge()
        self.image_sub = rospy.Subscriber("/kinect/rgb",Image,self.callback_rgb)      #Case 1
        self.image_sub = rospy.Subscriber("/kinect/depth",Image,self.callback_depth)  #Case 2

    def callback_rgb(self,data):
        cv_image_rgb = self.bridge.imgmsg_to_cv2(data, "bgr8")
        cv2.imshow("RGB_Sub", cv_image_rgb)
        if cv2.waitKey(1) & 0xFF == ord('q'):
            rospy.signal_shutdown('Quit')
            cv2.destroyAllWindows()

    def callback_depth(self, data):
        cv_image_depth = self.bridge.imgmsg_to_cv2(data, "bgr8")
        cv2.imshow("Depth_Sub", cv_image_depth)
        if cv2.waitKey(1) & 0xFF == ord('q'):
            rospy.signal_shutdown('Quit')
            cv2.destroyAllWindows()



def main():
    img_cvt = image_converter()
    rospy.init_node('image_converter', anonymous=True)
    try:
        rospy.spin()
    except KeyboardInterrupt:
        print("Shutting down")
if __name__ == '__main__':
    main()

Error:

(RGB_Sub:9479): Gtk-WARNING **: gtk_disable_setlocale() must be called before gtk_init()
[xcb] Unknown request in queue while dequeuing
[xcb] Most likely this is a multi-threaded client and XInitThreads has not been called
[xcb] Aborting, sorry about that.
python: ../../src/xcb_io.c:179: dequeue_pending_request: Assertion `!xcb_xlib_unknown_req_in_deq' failed.
Aborted (core dumped)
edit retag flag offensive close merge delete

3 Answers

Sort by ยป oldest newest most voted
1

answered 2020-11-20 03:53:51 -0500

Ranjit Kathiriya gravatar image
#!/usr/bin/env python
import sys
import message_filters ### ADD THIS
import rospy
import numpy as np
import math
from std_msgs.msg import String
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError
import cv2

#------Start of Class
class image_converter:
    def __init__(self):
        self.bridge = CvBridge()

        self.depth = message_filters.Subscriber('/camera/aligned_depth_to_color/image_raw', Image)
        self.color = message_filters.Subscriber('/camera/color/image_raw', Image)

    def callback(self,rgb,depth):
        cv_image_rgb = self.bridge.imgmsg_to_cv2(rgb, "bgr8")
        cv2.imshow("RGB_Sub", cv_image_rgb)
        cv_image_depth = self.bridge.imgmsg_to_cv2(depth, "bgr8")
        cv2.imshow("Depth_Sub", cv_image_depth)
        if cv2.waitKey(1) & 0xFF == ord('q'):
            rospy.signal_shutdown('Quit')
            cv2.destroyAllWindows()

def main():
    img_cvt = image_converter()
    rospy.init_node('image_converter', anonymous=True)
    try:
        ts = message_filters.ApproximateTimeSynchronizer([img_cvt.color,img_cvt.depth],10,0.1)
        ts.registerCallback(img_cvt.callback)
        rospy.spin()
    except KeyboardInterrupt:
        print("Shutting down")

if __name__ == '__main__':
    main()
edit flag offensive delete link more

Comments

Just change the topic and It will work fine.

Ranjit Kathiriya gravatar image Ranjit Kathiriya  ( 2020-11-20 03:54:47 -0500 )edit
2

answered 2019-01-08 04:31:10 -0500

Although, I'll be honest I don't recognise the error message you're getting I can see a bug in your code.

self.image_sub = rospy.Subscriber("/kinect/rgb",Image,self.callback_rgb)      #Case 1
self.image_sub = rospy.Subscriber("/kinect/depth",Image,self.callback_depth)  #Case 2

In these two lines you're writing the subscriber objects to the same variable self.image_sub so the second one should destroy the first. Try changing the these to two different identifiers, and see if the error continues.

edit flag offensive delete link more
1

answered 2019-01-08 06:10:13 -0500

robowarrior gravatar image

updated 2019-01-08 06:17:08 -0500

Yes, the second one would destroy the first one. But looks like you want to have both the information pieces accessible and process them at the same time. If that's the case, you need to use TimeSynchronizer from message_filters package. It allows you to have a single callback function for various topics. In your case, it would be:

#!/usr/bin/env python
import sys
import message_filters ### ADD THIS
import rospy
import numpy as np
import math
from std_msgs.msg import String
from sensor_msgs.msg import Image
from cv_bridge import CvBridge, CvBridgeError
import cv2

#------Start of Class
class image_converter:
    def __init__(self):
        self.bridge = CvBridge()
        self.image_rgb_sub = message_filters.Subscriber("/kinect/rgb",Image)      #Case 1
        self.image_depth_sub = message_filters.Subscriber("/kinect/depth",Image)  #Case 2

    def callback(self, rgb,depth):
        cv_image_rgb = self.bridge.imgmsg_to_cv2(rgb, "bgr8")
        cv2.imshow("RGB_Sub", cv_image_rgb)
        cv_image_depth = self.bridge.imgmsg_to_cv2(depth, "bgr8")
        cv2.imshow("Depth_Sub", cv_image_depth)
        if cv2.waitKey(1) & 0xFF == ord('q'):
            rospy.signal_shutdown('Quit')
            cv2.destroyAllWindows()

def main():
    img_cvt = image_converter()
    rospy.init_node('image_converter', anonymous=True)
    try:
        ts = message_filters.ApproximateTimeSynchronizer([img_cvt.image_rgb_sub,img_cvt.image_depth_sub],10,0.1)
        ts.registerCallback(callback)
        rospy.spin()
    except KeyboardInterrupt:
        print("Shutting down")

if __name__ == '__main__':
    main()

More info can be found on this documentation.

Peace!

edit flag offensive delete link more

Comments

I got new arror. this:

File "/home/junifer/catkin_ws/src/cv_bridge_python/src/Demo_Subcribe_2_topic_and_Display.py", line 33, in main
    ts.registerCallback(callback)
NameError: global name 'callback' is not defined
ToanJunifer gravatar image ToanJunifer  ( 2019-01-15 07:43:18 -0500 )edit

What should i do now ?

ToanJunifer gravatar image ToanJunifer  ( 2019-01-15 07:48:14 -0500 )edit

did you try ts.registerCallback(img_cvt.callback)

sheriarty gravatar image sheriarty  ( 2022-06-24 20:26:08 -0500 )edit

Question Tools

2 followers

Stats

Asked: 2019-01-08 03:04:39 -0500

Seen: 2,528 times

Last updated: Jan 08 '19