[Documentation] [TitleIndex] [WordIndex

  Show EOL distros: 

ros_comm: cpp_common | message_filters | perf_roscpp | rosbag | rosbagmigration | rosconsole | roscore_migration_rules | roscpp | roscpp_serialization | roscpp_traits | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostime | rostopic | roswtf | std_msgs | std_srvs | topic_tools | xmlrpcpp

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.

ros_comm: message_filters | perf_roscpp | rosbag | rosconsole | roscpp | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostopic | roswtf | std_srvs | topic_tools | xmlrpcpp

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.

ros_comm: message_filters | ros | rosbag | rosconsole | roscpp | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostopic | roswtf | std_srvs | topic_tools | xmlrpcpp

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)
ros_comm: message_filters | ros | rosbag | rosconsole | roscpp | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostopic | roswtf | std_srvs | topic_tools | xmlrpcpp

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)
ros_comm: message_filters | ros | rosbag | rosconsole | roscpp | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostopic | roswtf | std_srvs | topic_tools | xmlrpcpp

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)
ros_comm: message_filters | ros | rosbag | rosconsole | roscpp | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostopic | roswtf | std_srvs | topic_tools | xmlrpcpp

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)
ros_comm: message_filters | ros | rosbag | rosconsole | roscpp | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostopic | roswtf | std_srvs | topic_tools | xmlrpcpp

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)
ros_comm: message_filters | ros | rosbag | rosconsole | roscpp | rosgraph | rosgraph_msgs | roslaunch | roslisp | rosmaster | rosmsg | rosnode | rosout | rosparam | rospy | rosservice | rostest | rostopic | roswtf | std_srvs | topic_tools | xmlrpcpp

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: 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>, Jacob Perron <jacob AT openrobotics DOT org>
  • License: BSD
  • Source: git https://github.com/ros/ros_comm.git (branch: noetic-devel)

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++):

   1 FooFilter foo;
   2 BarFilter bar(foo);

or:

   1 FooFilter foo;
   2 BarFilter bar;
   3 bar.connectInput(foo);

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++

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

Output

Example (C++)

   1 message_filters::Subscriber<std_msgs::UInt32> sub(nh, "my_topic", 1);
   2 sub.registerCallback(myCallback);

is the equivalent of:

   1 ros::Subscriber sub = nh.subscribe("my_topic", 1, myCallback);

Example (Python)

   1 sub = message_filters.Subscriber("pose_topic", robot_msgs.msg.Pose)
   2 sub.registerCallback(myCallback)

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

Output

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

Output

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.

   1 message_filters::Subscriber<std_msgs::String> sub(nh, "my_topic", 1);
   2 message_filters::TimeSequencer<std_msgs::String> seq(sub, ros::Duration(0.1), ros::Duration(0.01), 10);
   3 seq.registerCallback(myCallback);

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

Output

In C++:

   1 message_filters::Subscriber<std_msgs::String> sub(nh, "my_topic", 1);
   2 message_filters::Cache<std_msgs::String> cache(sub, 100);
   3 cache.registerCallback(myCallback);

In Python:

   1 sub = message_filters.Subscriber('my_topic', sensor_msgs.msg.Image)
   2 cache = message_filters.Cache(sub, 100)

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.

   1 sub = message_filters.Subscriber('my_int_topic', std_msgs.msg.Int32)
   2 cache = message_filters.Cache(sub, 100, allow_headerless=True)
   3 # the cache assigns current ROS time as each message's timestamp

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

Output

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

Output

Examples (C++)

Simple Example

   1 void myCallback(const MsgConstPtr& msg)
   2 {
   3 }
   4 
   5 Chain<Msg> c;
   6 c.addFilter(boost::shared_ptr<Subscriber<Msg> >(new Subscriber<Msg>));
   7 c.addFilter(boost::shared_ptr<TimeSequencer<Msg> >(new TimeSequencer<Msg>));
   8 c.registerCallback(myCallback);

Bare Pointers

It is possible to pass bare pointers in. These will not be automatically deleted when Chain is destructed.

   1 Chain<Msg> c;
   2 Subscriber<Msg> s;
   3 c.addFilter(&s);
   4 c.registerCallback(myCallback);

Retrieving a Filter

   1 Chain<Msg> c;
   2 size_t sub_index = c.addFilter(boost::shared_ptr<Subscriber<Msg> >(new Subscriber<Msg>));
   3 
   4 boost::shared_ptr<Subscriber<Msg> > sub = c.getFilter<Subscriber<Msg> >(sub_index);


2024-03-16 12:45