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

rospy subscriber with multiple input

asked 2017-10-17 04:30:48 -0600

marcoresk gravatar image

updated 2017-10-17 08:05:57 -0600

My ROS rqt plugin now works with single subscription, like

#some lines of plugin initialization from .ui file
self._c.Action_button.clicked.connect(self.visual_callback) #callback started when button is pressed

# other several lines of plugin initialization code
def visual_callback(self):
        self.left_topic = "/my_stereo/left/image_raw"
        try: #Subscription + Callback number 1, with 1 input
            self.bridge0 = CvBridge()
            self.image_sub0 = rospy.Subscriber(self.left_topic,Image,self.left_callback,queue_size=1)
        except ValueError, e:
            rospy.logerr('My Plugin: Error connecting topic (%s)'%e)
        self.right_topic = "/my_stereo/right/image_raw"

        try: #Subscription + Callback number 2, with 1 input
            self.bridge1 = CvBridge()
            self.image_sub1 = rospy.Subscriber(self.right_topic,Image,self.right_callback,queue_size=1)
        except ValueError, e:
            rospy.logerr('My Plugin: Error connecting topic (%s)'%e)

I would like to create a new callback that uses in input both the "left" Image signal and the "right" Image signal. The rospy subscriber structure is fantastic, as it launches the callbacks and spin it automatically. Can I use something similar to subscribe both image topics and launch a single callback with 2 input?

A - I tried this method but I could not make rospy.spin work into a rqt plugin (I hope it would be my fault only, any hints?)

def visual_callback2(self, left, right):
    if True:
        left = message_filters.Subscriber("/my_stereo/left/image_raw", Image)
        right = message_filters.Subscriber("/my_stereo/right/image_raw", Image)
        print "Double subscribe!!"
        ts = message_filters.TimeSynchronizer([left, right], 10) #exact sync
        #ts = message_filters.ApproximateTimeSynchronizer([left, right], 10, 0.1, allow_headerless=True) #approxiamte sync
        ts.registerCallback(self.visual_callback2)
        #self.maker(left,right) #external function with 2 arguments
        #rospy.spin() #this should update continuously, but it does not work

B - I do not need stereo_image_proc or similar suggestion, that is not my goal. I want to write my personal callback with 2 image inputs in my rqt plugin.

edit retag flag offensive close merge delete

3 Answers

Sort by ยป oldest newest most voted
1

answered 2017-11-05 14:48:17 -0600

Ed Venator gravatar image

I think your solution with message filters is pretty close to the solution you need, except that you're putting the subscriber creation inside your callback, and that doesn't make sense.

I think the solution looks something like this:

# some lines of plugin initialization from .ui file
# callback started when button is pressed
self._c.Action_button.clicked.connect(self.visual_callback)

def visual_callback(self):
    """ This function is triggered by pressing the connect button."""
    # Create subscribers for each topic
    self.left = message_filters.Subscriber("/my_stereo/left/image_raw", Image)
    self.right = message_filters.Subscriber("/my_stereo/right/image_raw", Image)
    # Create synce filter. Use exact or approximate as appropriate.
    self.ts = message_filters.TimeSynchronizer([left, right], 10)
    # Assuming your object has a method maker(left, right) that takes in two Image objects
    self.ts.registerCallback(self.maker)
    # rospy.spin() is not desired here, as all it does is run an infinite loop
edit flag offensive delete link more

Comments

Thank you for help. It make more sense. However, It still does not work (or, at least, the maker callback seems not to be activated: I commented all the maker callback except for a print instruction). I also tried to set self.left and self.riht as argument of TimeSynchronizer.

marcoresk gravatar image marcoresk  ( 2017-11-20 08:39:20 -0600 )edit

Hold on! The time ApproximateTimeSynchronizer strategy works (not the TimwSynchronizer one)! the parameter allow_headerless is not permitted in ROS Indigo and I was forced to remove it. But your solution now works.

marcoresk gravatar image marcoresk  ( 2017-11-20 08:54:24 -0600 )edit
0

answered 2017-10-17 04:39:56 -0600

tulku gravatar image

updated 2017-10-17 04:57:47 -0600

Hi!

I'm not really sure if I understand the problem fully. But what happens if you follow method A, but omit the rospy.spin()?

rospy.spin() is usually used when you don't want to do nothing more, and just wait for the callbacks to get triggered. This is no te case, as rqt will still need to do things.

EDIT based on on your comment. I do not know what triggers the 'visual_callback' in your code (if that's the one you are stating that runs only once). More code/information is needed to better understand your problem.

edit flag offensive delete link more

Comments

If I omit rospy.spin() the callback runs once and stops: I do not want this. I would like to write a callback continuously updated as the callbacks in rospy.Subscriber are.

marcoresk gravatar image marcoresk  ( 2017-10-17 04:50:30 -0600 )edit

@tulku I update the code: the main callback is simply triggered by pressing a button in my rqt plugin. There are no more lines in this plugin at the moment, after the lines of import and the plugin initialization/connection with the .ui file

marcoresk gravatar image marcoresk  ( 2017-10-17 05:08:34 -0600 )edit

Can you please add the code of the modified version, when you tried method A?

tulku gravatar image tulku  ( 2017-10-17 05:45:39 -0600 )edit

@tulku I added my try with the sync method, I can't say where the main error is. Thank you in advance.

marcoresk gravatar image marcoresk  ( 2017-10-17 08:05:59 -0600 )edit
0

answered 2017-10-23 06:25:24 -0600

You can use the same callback to subscribe to different topics and check the type of the received message (seeing msg._type) on the callback.

If you are subscribing to two different topics that published messages of types sensor_msgs/LaserScan and nav_msgs/Odometry, for example, then your callback would be something like:

def common_callback(self, msg):

        input_message_type = str(msg._type)

        rospy.logdebug("msg._type: "+input_message_type)

        if input_message_type == "sensor_msgs/LaserScan":
            rospy.loginfo("sub_laserscan called me, with type msg: "+input_message_type)
            # doSomething()

        elif input_message_type == "nav_msgs/Odometry":
            rospy.loginfo("sub_odom called me, with type msg==>"+input_message_type)
            # doSomethingElse()

This callback example I got from this answer.

edit flag offensive delete link more

Comments

1

@marcoresk wrote:

I would like to create a new callback that uses in input both the "left" Image signal and the "right" Image signal

Could you add some more detail to show how checking msg._type makes that possible?

gvdhoorn gravatar image gvdhoorn  ( 2017-10-23 06:35:53 -0600 )edit

Since the topics are /my_stereo/left/image_raw and /my_stereo/right/image_raw, the same callback can subscribe to both topics.

On the callback, by checking the msg._type it can decide if the image comes from the left or right "signal".

Did I misunderstand the question?

Ruben Alves gravatar image Ruben Alves  ( 2017-10-23 07:53:17 -0600 )edit

It's an image_raw topic on both sides, so I assume a sensor_msgs/Image. Checking the type won't help afaict.

gvdhoorn gravatar image gvdhoorn  ( 2017-10-23 07:54:33 -0600 )edit

@Ruben Alves both messages are Image messages, and the point of my question is not how to decide if the video comes from left or from right. The point is to have a callback that can have 2 inputs and continuously updated as a "single input callback" in the classic subscription struct. showed above

marcoresk gravatar image marcoresk  ( 2017-10-23 08:46:21 -0600 )edit

Question Tools

2 followers

Stats

Asked: 2017-10-17 04:30:48 -0600

Seen: 1,474 times

Last updated: Nov 05 '17