Package Summary

Improved ROS message filters

  • Maintainer status: developed
  • Maintainer: Timo Röhling <timo.roehling AT fkie.fraunhofer DOT de>
  • Author: Timo Röhling <timo.roehling AT fkie.fraunhofer DOT de>
  • License: Apache-2.0
  • Source: git https://github.com/fkie/message_filters.git (branch: master)

Package Summary

Improved ROS message filters

  • Maintainer status: maintained
  • Maintainer: Timo Röhling <timo.roehling AT fkie.fraunhofer DOT de>
  • Author: Timo Röhling <timo.roehling AT fkie.fraunhofer DOT de>
  • License: Apache-2.0
  • Source: git https://github.com/fkie/message_filters.git (branch: master)

Overview

This library is a replacement for the ROS message_filters package. It is written in modern C++ and more type-safe than the original version.

The data flow is modeled with a pipeline metaphor, where data always flows from a source to a sink. A filter is both source and sink for data, possibly with different data types. For integration with ROS, the library provides a number of subscribers and publishers which act as sources or sinks of the data flow.

Language Requirements

The library requires C++14 or better. Starting with Ubuntu 18.04 (ROS Melodic), GCC uses C++14 as default dialect. For older versions, you may or may not succeed by passing the command line option -std=gnu++1y to the compiler.

Design

The filters are written to be as data agnostic as possible. Therefore, many filters can process arbitrary data types and are not restricted to ROS messages. A few filters need access to ROS header information, such as time stamp or TF frame identifier.

Sources and sinks are strongly typed, i.e., each source will only pass on data of a particular type, and each sink will only accept data of a particular type. The compiler will error out if you try to connect incompatible filters. As the strong typing relies on the C++ template mechanism, the error messages can be quite verbose and difficult to parse sometimes (looking at you, GCC).

The library filters support arbitrary arities, i.e., the grouping of multiple data types, where items of different types are combined and passed on as a unit. This is particularly useful to process messages from distinct topics which belong together conceptually, e.g., the sensor_msgs::Image and sensor_msgs::CameraInfo messages from a calibrated camera.

Getting Started

While you are free to derive your own classes from the one of the base classes, most programs will want to register a custom callback function for their application logic.

The SimpleUserFilter works almost like a regular ROS callback, but it expects a boolean return value that determines if the data is passed on to subsequent filters in the pipeline (if any), or if processing terminates. You can use this type of filter to consume data at the end of the pipeline, or if you want to remove invalid inputs before further processing occurs.

The UserFilter is more generic and can be used if your filter outputs differ from its inputs. You can implement pretty much any kind of transforming filter.

The UserSource is a simple data source which can be used as callback in third-party code.

As a simple "Hello World" example, consider:

   1 #include <ros/ros.h>
   2 #include <std_msgs/String.h>
   3 #include <fkie_message_filters/fkie_message_filters.h>
   4 
   5 namespace mf = fkie_message_filters;
   6 
   7 using StringSubscriber = mf::Subscriber<std_msgs::String, mf::RosMessage>;
   8 using StringPublisher = mf::Publisher<std_msgs::String, mf::RosMessage>;
   9 using GreetingFilter = mf::UserFilter<
  10                               StringSubscriber::Output,
  11                               StringPublisher::Input
  12                        >;
  13 
  14 int main(int argc, char** argv)
  15 {
  16     ros::init(argc, argv, "hello");
  17     ros::NodeHandle nh;
  18     StringSubscriber sub(nh, "name", 1);
  19     StringPublisher pub(nh, "greeting", 1);
  20     GreetingFilter flt;
  21     flt.set_processing_function(
  22         [](const std_msgs::String& input,
  23            const GreetingFilter::CallbackFunction& output)
  24         {
  25             std_msgs::String greeting;
  26             greeting.data = "Hello, " + input.data + "!";
  27             output(greeting);
  28         }
  29     );
  30     mf::chain(sub, flt, pub);
  31     ros::spin();
  32     return 0;
  33 }

The user-defined filter accepts a std_msgs::String message with a name as input and composes a new std_msgs::String message with a personalized greeting as output. Note that each source can have arbitrarily many sinks connected to it, and vice versa, so the simplicity of the three-link chain in this example is by no means a limitation of the library.

Available Filters

See the API documentation for more details.

  • Buffer: Store and forward data

  • CameraPublisher: Publish consumed data to a ROS camera topic

  • CameraSubscriber: Subscribe to a ROS camera topic as data provider

  • Combiner: Combine multiple sinks into a single source with one of the following policies:

    • Fifo: First-In-First-Out

    • ExactTime: Exactly matching time stamp

    • ApproximateTime: Approximately matching time stamp

  • Divider: Split source with multiple inputs into independent output sinks

  • ImagePublisher: Publish consumed data to a ROS image topic

  • ImageSubscriber: Subscribe to a ROS image topic as data provider

  • Publisher: Publish consumed data on a ROS topic

  • Selector: Choose an arbitrary set of inputs to be forwarded

  • Sequencer: Enforce correct temporal order

  • SimpleUserFilter: Simplified filter with user-defined callback function

  • Subscriber: Subscribe to a ROS topic as data provider

  • TfFilter: Wait for TF transformations for incoming messages

  • UserFilter: Generic filter with user-defined callback function

  • UserSource: Manually operated data source

Implementation Details

The pipeline processing is executed by nested calls to receive and send functions. The library is thread-safe and guarantees basic exception safety, but you are expected to handle your own exceptions in your callbacks. Exceptions which propagate through library code will abort processing for the offending message immediately, even if not all downstream sinks have received the message yet. If there is no upstream user-defined filter that catches the exception, the uncaught exception will eventually terminate the program. The library will detect cycles in the pipeline and abort with a std::logic_error exception.

Certain filters, such as the Buffer or the TfFilter, can interoperate with ROS callback queues for convenient workload scheduling.

Wiki: fkie_message_filters (last edited 2020-09-02 08:15:32 by TimoRöhling)