Show EOL distros:
Package Summary
A set of message filters which take in messages and may output those messages at a later time, based on the conditions that filter needs met.
- Author: Josh Faust (jfaust@willowgarage.com), Vijay Pradeep (vpradeep@willowgarage.com)
- License: BSD
- External website: http://pr.willowgarage.com/wiki/message_filters
- Repository: ros
- Source: svn https://code.ros.org/svn/ros/stacks/ros_comm/tags/ros_comm-1.4.8
Package Summary
A set of message filters which take in messages and may output those messages at a later time, based on the conditions that filter needs met.
- Author: Josh Faust (jfaust@willowgarage.com), Vijay Pradeep (vpradeep@willowgarage.com)
- License: BSD
- Source: git https://github.com/ros/ros_comm.git (branch: ros_comm-1.6)
Package Summary
A set of message filters which take in messages and may output those messages at a later time, based on the conditions that filter needs met.
- Author: Josh Faust (jfaust@willowgarage.com), Vijay Pradeep (vpradeep@willowgarage.com)
- License: BSD
- Source: git https://github.com/ros/ros_comm.git (branch: fuerte-devel)
Package Summary
A set of message filters which take in messages and may output those messages at a later time, based on the conditions that filter needs met.
- Maintainer status: maintained
- Maintainer: Dirk Thomas <dthomas AT osrfoundation DOT org>
- Author: Josh Faust, Vijay Pradeep
- License: BSD
- Source: git https://github.com/ros/ros_comm.git (branch: groovy-devel)
Package Summary
A set of message filters which take in messages and may output those messages at a later time, based on the conditions that filter needs met.
- Maintainer status: maintained
- Maintainer: Dirk Thomas <dthomas AT osrfoundation DOT org>
- Author: Josh Faust, Vijay Pradeep
- License: BSD
- Source: git https://github.com/ros/ros_comm.git (branch: hydro-devel)
Package Summary
A set of message filters which take in messages and may output those messages at a later time, based on the conditions that filter needs met.
- Maintainer status: maintained
- Maintainer: Dirk Thomas <dthomas AT osrfoundation DOT org>
- Author: Josh Faust, Vijay Pradeep
- License: BSD
- Source: git https://github.com/ros/ros_comm.git (branch: indigo-devel)
Package Summary
A set of message filters which take in messages and may output those messages at a later time, based on the conditions that filter needs met.
- Maintainer status: maintained
- Maintainer: Dirk Thomas <dthomas AT osrfoundation DOT org>
- Author: Josh Faust, Vijay Pradeep
- License: BSD
- Source: git https://github.com/ros/ros_comm.git (branch: indigo-devel)
Package Summary
A set of message filters which take in messages and may output those messages at a later time, based on the conditions that filter needs met.
- Maintainer status: maintained
- Maintainer: Jacob Perron <jacob AT openrobotics DOT org>, Michael Carroll <michael AT openrobotics DOT org>, Shane Loretz <sloretz AT openrobotics DOT org>
- Author: Josh Faust, Vijay Pradeep, Dirk Thomas <dthomas AT osrfoundation DOT org>
- License: BSD
- Source: git https://github.com/ros/ros_comm.git (branch: kinetic-devel)
Package Summary
A set of message filters which take in messages and may output those messages at a later time, based on the conditions that filter needs met.
- Maintainer status: maintained
- Maintainer: Dirk Thomas <dthomas AT osrfoundation DOT org>
- Author: Josh Faust, Vijay Pradeep
- License: BSD
- Source: git https://github.com/ros/ros_comm.git (branch: lunar-devel)
Package Summary
A set of message filters which take in messages and may output those messages at a later time, based on the conditions that filter needs met.
- Maintainer status: maintained
- Maintainer: Jacob Perron <jacob AT openrobotics DOT org>, Michael Carroll <michael AT openrobotics DOT org>, Shane Loretz <sloretz AT openrobotics DOT org>
- Author: Josh Faust, Vijay Pradeep, Dirk Thomas <dthomas AT osrfoundation DOT org>
- License: BSD
- Source: git https://github.com/ros/ros_comm.git (branch: melodic-devel)
Package Summary
A set of message filters which take in messages and may output those messages at a later time, based on the conditions that filter needs met.
- Maintainer status: maintained
- Maintainer: Jacob Perron <jacob AT openrobotics DOT org>, Michael Carroll <michael AT openrobotics DOT org>, Shane Loretz <sloretz AT openrobotics DOT org>
- Author: Josh Faust, Vijay Pradeep, Dirk Thomas <dthomas AT osrfoundation DOT org>
- License: BSD
- Source: git https://github.com/ros/ros_comm.git (branch: noetic-devel)
Contents
Overview
message_filters is a utility library for use with roscpp and rospy. It collects commonly used message "filtering" algorithms into a common space. A message filter is defined as something which a message arrives into and may or may not be spit back out of at a later point in time.
An example is the time synchronizer, which takes in messages of different types from multiple sources, and outputs them only if it has received a message on each of those sources with the same timestamp.
Filter Pattern
All message filters follow the same pattern for connecting inputs and outputs. Inputs are connected either through the filter's constructor or through the connectInput() method. Outputs are connected through the registerCallback() method.
Note that the input and output types are defined per-filter, so not all filters are directly interconnectable.
For example, given two filters FooFilter and BarFilter where FooFilter's output is compatible with BarFilter's input, connecting foo to bar could be (in C++):
or:
in Python:
1 bar(foo)
1 bar.connectInput(foo)
To then connect bar's output to your own callback function:
1 bar.registerCallback(myCallback);
The signature of myCallback is dependent on the definition of BarFilter.
registerCallback()
You can register multiple callbacks with the registerCallbacks() method. They will get called in the order they are registered.
C++
In C++ registerCallback() returns a message_filters::Connection object that allows you to disconnect the callback by calling its disconnect() method. You do not need to store this connection object if you do not need to manually disconnect the callback.
Subscriber
See also: C++ message_filters::Subscriber API docs Python message_filters.Subscriber
The Subscriber filter is simply a wrapper around a ROS subscription that provides a source for other filters. The Subscriber filter cannot connect to another filter's output, instead it uses a ROS topic as its input.
Connections
Input
- No input connections
Output
C++: void callback(const boost::shared_ptr<M const>&) Python: callback(msg)
Example (C++)
is the equivalent of:
1 ros::Subscriber sub = nh.subscribe("my_topic", 1, myCallback);
Example (Python)
Time Synchronizer
See also: C++ message_filters::TimeSynchronizer API docs, Python message_filters.TimeSynchronizer
The TimeSynchronizer filter synchronizes incoming channels by the timestamps contained in their headers, and outputs them in the form of a single callback that takes the same number of channels. The C++ implementation can synchronize up to 9 channels.
Connections
Input
C++: Up to 9 separate filters, each of which is of the form void callback(const boost::shared_ptr<M const>&). The number of filters supported is determined by the number of template arguments the class was created with. Python: N separate filters, each of which has signature callback(msg).
Output
C++: For message types M0..M8, void callback(const boost::shared_ptr<M0 const>&, ..., const boost::shared_ptr<M8 const>&). The number of parameters is determined by the number of template arguments the class was created with. Python: callback(msg0.. msgN). The number of parameters is determined by the number of template arguments the class was created with.
Example (C++)
Suppose you are writing a ROS node that needs to process data from two time synchronized topics. Your program will probably look something like this:
1 #include <message_filters/subscriber.h>
2 #include <message_filters/time_synchronizer.h>
3 #include <sensor_msgs/Image.h>
4 #include <sensor_msgs/CameraInfo.h>
5
6 using namespace sensor_msgs;
7 using namespace message_filters;
8
9 void callback(const ImageConstPtr& image, const CameraInfoConstPtr& cam_info)
10 {
11 // Solve all of perception here...
12 }
13
14 int main(int argc, char** argv)
15 {
16 ros::init(argc, argv, "vision_node");
17
18 ros::NodeHandle nh;
19
20 message_filters::Subscriber<Image> image_sub(nh, "image", 1);
21 message_filters::Subscriber<CameraInfo> info_sub(nh, "camera_info", 1);
22 TimeSynchronizer<Image, CameraInfo> sync(image_sub, info_sub, 10);
23 sync.registerCallback(boost::bind(&callback, _1, _2));
24
25 ros::spin();
26
27 return 0;
28 }
(Note: In this particular case you could use the CameraSubscriber class from image_transport, which essentially wraps the filtering code above.)
Example (Python)
1 import message_filters
2 from sensor_msgs.msg import Image, CameraInfo
3
4 def callback(image, camera_info):
5 # Solve all of perception here...
6
7 image_sub = message_filters.Subscriber('image', Image)
8 info_sub = message_filters.Subscriber('camera_info', CameraInfo)
9
10 ts = message_filters.TimeSynchronizer([image_sub, info_sub], 10)
11 ts.registerCallback(callback)
12 rospy.spin()
Time Sequencer
See also: C++ message_filters::TimeSequencer API docs
Python: the TimeSequencer filter is not yet implemented.
The TimeSequencer filter guarantees that messages will be called in temporal order according to their header's timestamp. The TimeSequencer is constructed with a specific delay which specifies how long to queue up messages before passing them through. A callback for a message is never invoked until the messages' time stamp is out of date by at least delay. However, for all messages which are out of date by at least the delay, their callback are invoked and guaranteed to be in temporal order. If a message arrives from a time prior to a message which has already had its callback invoked, it is thrown away.
Connections
Input
C++: void callback(const boost::shared_ptr<M const>&)
Output
C++: void callback(const boost::shared_ptr<M const>&)
Example (C++)
The C++ version takes both a delay an an update rate. The update rate determines how often the sequencer will check its queue for messages that are ready to be pass through. The last argument is the number of messages to queue up before beginning to throw some away.
Cache
See also: C++ message_filters::Cache API docs Python message_filters.Cache
Stores a time history of messages.
Given a stream of messages, the most recent N messages are cached in a ring buffer, from which time intervals of the cache can then be retrieved by the client. The timestamp of a message is determined from its header field.
If the message type doesn't contain a header, see below for workaround.
The Cache immediately passes messages through to its output connections.
Connections
Input
C++: void callback(const boost::shared_ptr<M const>&) Python: callback(msg)
Output
C++: void callback(const boost::shared_ptr<M const>&) Python: callback(msg)
In C++:
In Python:
In this example, the Cache stores the last 100 messages received on my_topic, and myCallback is called on the addition of every new message. The user can then make calls like cache.getInterval(start, end) to extract part of the cache.
If the message type does not contain a header field that is normally used to determine its timestamp, and the Cache is contructed with allow_headerless=True, the current ROS time is used as the timestamp of the message. This is currently only available in Python.
Policy-Based Synchronizer [ROS 1.1+]
The Synchronizer filter synchronizes incoming channels by the timestamps contained in their headers, and outputs them in the form of a single callback that takes the same number of channels. The C++ implementation can synchronize up to 9 channels.
The Synchronizer filter is templated on a policy that determines how to synchronize the channels. There are currently two policies: ExactTime and ApproximateTime.
C++ Header: message_filters/synchronizer.h
Connections
Input
C++: Up to 9 separate filters, each of which is of the form void callback(const boost::shared_ptr<M const>&). The number of filters supported is determined by the number of template arguments the class was created with. Python: N separate filters, each of which has signature callback(msg).
Output
C++: For message types M0..M8, void callback(const boost::shared_ptr<M0 const>&, ..., const boost::shared_ptr<M8 const>&). The number of parameters is determined by the number of template arguments the class was created with. Python: callback(msg0.. msgN). The number of parameters is determined by the number of template arguments the class was created with.
ExactTime Policy
The message_filters::sync_policies::ExactTime policy requires messages to have exactly the same timestamp in order to match. Your callback is only called if a message has been received on all specified channels with the same exact timestamp. The timestamp is read from the header field of all messages (which is required for this policy).
C++ Header: message_filters/sync_policies/exact_time.h
Example (C++)
1 #include <message_filters/subscriber.h>
2 #include <message_filters/synchronizer.h>
3 #include <message_filters/sync_policies/exact_time.h>
4 #include <sensor_msgs/Image.h>
5 #include <sensor_msgs/CameraInfo.h>
6
7 using namespace sensor_msgs;
8 using namespace message_filters;
9
10 void callback(const ImageConstPtr& image, const CameraInfoConstPtr& cam_info)
11 {
12 // Solve all of perception here...
13 }
14
15 int main(int argc, char** argv)
16 {
17 ros::init(argc, argv, "vision_node");
18
19 ros::NodeHandle nh;
20 message_filters::Subscriber<Image> image_sub(nh, "image", 1);
21 message_filters::Subscriber<CameraInfo> info_sub(nh, "camera_info", 1);
22
23 typedef sync_policies::ExactTime<Image, CameraInfo> MySyncPolicy;
24 // ExactTime takes a queue size as its constructor argument, hence MySyncPolicy(10)
25 Synchronizer<MySyncPolicy> sync(MySyncPolicy(10), image_sub, info_sub);
26 sync.registerCallback(boost::bind(&callback, _1, _2));
27
28 ros::spin();
29
30 return 0;
31 }
ApproximateTime Policy
The message_filters::sync_policies::ApproximateTime policy uses an adaptive algorithm to match messages based on their timestamp.
The timestamp is determined from the header field of the message (which is required).
If not all messages have a header field from which the timestamp could be determined, see below for a workaround.
C++ Header: message_filters/sync_policies/approximate_time.h
Example (C++)
1 #include <message_filters/subscriber.h>
2 #include <message_filters/synchronizer.h>
3 #include <message_filters/sync_policies/approximate_time.h>
4 #include <sensor_msgs/Image.h>
5
6 using namespace sensor_msgs;
7 using namespace message_filters;
8
9 void callback(const ImageConstPtr& image1, const ImageConstPtr& image2)
10 {
11 // Solve all of perception here...
12 }
13
14 int main(int argc, char** argv)
15 {
16 ros::init(argc, argv, "vision_node");
17
18 ros::NodeHandle nh;
19 message_filters::Subscriber<Image> image1_sub(nh, "image1", 1);
20 message_filters::Subscriber<Image> image2_sub(nh, "image2", 1);
21
22 typedef sync_policies::ApproximateTime<Image, Image> MySyncPolicy;
23 // ApproximateTime takes a queue size as its constructor argument, hence MySyncPolicy(10)
24 Synchronizer<MySyncPolicy> sync(MySyncPolicy(10), image1_sub, image2_sub);
25 sync.registerCallback(boost::bind(&callback, _1, _2));
26
27 ros::spin();
28
29 return 0;
30 }
If some messages are of a type that doesn't contain the header field, ApproximateTimeSynchronizer refuses by default adding such messages. However, its Python version can be constructed with allow_headerless=True, which uses current ROS time in place of any missing header.stamp field:
1 import message_filters
2 from std_msgs.msg import Int32, Float32
3
4 def callback(mode, penalty):
5 # The callback processing the pairs of numbers that arrived at approximately the same time
6
7 mode_sub = message_filters.Subscriber('mode', Int32)
8 penalty_sub = message_filters.Subscriber('penalty', Float32)
9
10 ts = message_filters.ApproximateTimeSynchronizer([mode_sub, penalty_sub], 10, 0.1, allow_headerless=True)
11 ts.registerCallback(callback)
12 rospy.spin()
Chain [ROS 1.1+]
See also: C++ API Docs
The Chain filter allows you to dynamically chain together multiple single-input/single-output (simple) filters. As filters are added to it they are automatically connected together in the order they were added. It also allows you to retrieve added filters by index.
Chain is most useful for cases where you want to determine which filters to apply at runtime rather than compile-time.
Connections
Input
C++: void callback(const boost::shared_ptr<M const>&)
Output
C++: void callback(const boost::shared_ptr<M const>&)
Examples (C++)
Simple Example
Bare Pointers
It is possible to pass bare pointers in. These will not be automatically deleted when Chain is destructed.
Retrieving a Filter