message_filters package

Module contents

Message Filter Objects.

class message_filters.ApproximateTimeSynchronizer(fs, queue_size, slop, allow_headerless=False)

Bases: TimeSynchronizer

Approximately synchronizes messages by their timestamps.

ApproximateTimeSynchronizer synchronizes incoming message filters by the timestamps contained in their messages’ headers. The API is the same as TimeSynchronizer except for an extra slop parameter in the constructor that defines the delay (in seconds) with which messages can be synchronized. The allow_headerless option specifies whether to allow storing headerless messages with current ROS time instead of timestamp. You should avoid this as much as you can, since the delays are unpredictable.

add(msg, my_queue, my_queue_index=None)
class message_filters.Cache(f, cache_size=1, allow_headerless=False)

Bases: SimpleFilter

Stores a time history of messages.

Given a stream of messages, the most recent cache_size messages are cached in a ring buffer, from which time intervals of the cache can then be retrieved by the client. The allow_headerless option specifies whether to allow storing headerless messages with current ROS time instead of timestamp. You should avoid this as much as you can, since the delays are unpredictable.

add(msg)
connectInput(f)
getElemAfterTime(stamp)

Return the oldest element after or equal the passed time stamp.

getElemBeforeTime(stamp)

Return the newest element before or equal the passed time stamp.

getInterval(from_stamp, to_stamp)

Query the current cache content between from_stamp to to_stamp.

getLast()
getLastestTime()

Return the newest recorded timestamp.

getOldestTime()

Return the oldest recorded timestamp.

class message_filters.SimpleFilter

Bases: object

registerCallback(cb, *args)

Register a callback cb to be called when this filter has output.

The filter calls the function cb with a filter-dependent.

list of arguments,followed by the call-supplied arguments args..

signalMessage(*msg)
class message_filters.Subscriber(*args, **kwargs)

Bases: SimpleFilter

ROS 2 subscription filter, takes identical arguments as rclpy.Subscriber.

This class acts as a highest-level filter, simply passing messages from a ROS 2 subscription through to the filters which have connected to it.

callback(msg)
getTopic()
class message_filters.TimeSynchronizer(fs, queue_size)

Bases: SimpleFilter

Synchronizes messages by their timestamps.

TimeSynchronizer synchronizes incoming message filters by the timestamps contained in their messages’ headers. TimeSynchronizer listens on multiple input message filters fs, and invokes the callback when it has a collection of messages with matching timestamps.

The signature of the callback function is:

def callback(msg1, … msgN):

where N is the number of input message filters, and each message is the output of the corresponding filter in fs. The required queue size parameter specifies how many sets of messages it should store from each input filter (by timestamp) while waiting for messages to arrive and complete their “set”.

add(msg, my_queue, my_queue_index=None)
connectInput(fs)