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

Unsubscribe a message_filters.ApproximateTimeSynchronizer

asked 2018-09-14 07:31:13 -0500

Mehdi. gravatar image

I have a subscriber setup to subscribe to three topics simultaneously (using message_filters). i want to stop this subscriber. Unfortunately, there is no mention of any "unregister" function in the documentation.

How can I do that?

edit retag flag offensive close merge delete

1 Answer

Sort by ยป oldest newest most voted
0

answered 2018-12-03 07:05:01 -0500

Mehdi. gravatar image

I finally found and answer to this on the Github Issues Here is an example code of a callback receiving data from 3 topics simultaneously and unsubscribing after 40 messages are received:

#!/usr/bin/env python
import message_filters
import rospy
from sensor_msgs.msg import Image, LaserScan, PointCloud2


def image_cb(depth_img, intensity_img, cloud):
    global subs, counter
    rospy.loginfo_throttle(1, "Receiving data")
    counter += 1
    if counter > 40:
        rospy.loginfo("100 samples, trying to unsubscribe")
        [sub.sub.unregister() for sub in subs]

counter = 0
rospy.init_node("test")
depth_sub = message_filters.Subscriber("/pico_flexx_rear/image_depth", Image)
intensity_sub = message_filters.Subscriber("/pico_flexx_rear/image_mono16",
                                           Image)
cloud_sub = message_filters.Subscriber("/pico_flexx_rear/points",
                                       PointCloud2)
subs = [depth_sub, intensity_sub, cloud_sub]
ts = message_filters.ApproximateTimeSynchronizer(subs, 10, 1)
ts.registerCallback(image_cb)
rospy.spin()

As you see here, one could just iterate over the message_filters.Subscriber variable and call the message_filters.Subscriber.sub.unregister() function in order to unsubscribe.

edit flag offensive delete link more

Question Tools

1 follower

Stats

Asked: 2018-09-14 07:31:13 -0500

Seen: 1,518 times

Last updated: Dec 03 '18