C++ API
FKIE Message Filters
The fkie_message_filters library is a replacement for the ROS message_filters package. It is written in modern C++ and more type-safe than the original version.
Overview
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.
Getting Started
While you are free to derive your own filters from the basic source and sink classes, it is most likely better to integrate the application logic with custom callback functions.
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.
A third filter UserSource is a simple data source which can be used as callback in third-party code.
As a simple “Hello World” example, consider:
#include <fkie_message_filters/fkie_message_filters.hpp>
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/string.hpp>
namespace mf = fkie_message_filters;
using StringSubscriber = mf::Subscriber<std_msgs::msg::String, mf::RosMessage>;
using StringPublisher = mf::Publisher<std_msgs::msg::String, mf::RosMessage>;
using GreetingFilter = mf::UserFilter<StringSubscriber::Output, StringPublisher::Input>;
int main(int argc, char** argv)
{
rclcpp::init(argc, argv);
rclcpp::Node::SharedPtr node = std::make_shared<rclcpp::Node>("hello");
StringSubscriber sub(node, "name");
StringPublisher pub(node, "greeting");
GreetingFilter flt;
flt.set_processing_function(
[](const std_msgs::msg::String& input, const GreetingFilter::CallbackFunction& output)
{
std_msgs::msg::String greeting;
greeting.data = "Hello, " + input.data + "!";
output(greeting);
});
mf::chain(sub, flt, pub);
rclcpp::spin(node);
return 0;
}
The user-defined filter accepts a std_msgs::msg::String message with a name as input and composes a new std_msgs::msg::String message with a personalized greeting as output. Note that each source can have arbitrarily many sinks connected to it, and vice vera, so the simplicity of the three-link chain in this example is by no means a limitation of the library.
Data Types
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 (looking at you, GCC). It is very much recommended to use the Input and Output typedefs which are provided by every filter.
Starting with version 2.0, the library supports std::unique_ptr and other noncopyable but movable types. Sources which use these types can only have a single sink connected for obvious reasons, though.
N-ary filters
All sources and sinks support 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::msg::Image and sensor_msgs::msg::CameraInfo messages from a calibrated camera. N-ary filters can be created, rearranged, and broken up using the Combiner , Divider , and Selector filters.
Implementation Details
Generally, 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.
Class Hierarchy
-
- Namespace fkie_message_filters
- Namespace fkie_message_filters::combiner_policies
- Template Class ApproximateTime
- Template Class ExactTime
- Template Class Fifo
- Template Class Latch
- Template Class PolicyBase
- Template Struct RosMessage
- Template Struct RosMessageSharedPtr
- Template Struct RosMessageUniquePtr
- Template Class Buffer
- Struct Buffer::Impl
- Class Impl::BufferCB
- Struct Buffer::Impl
- Template Class CameraPublisher
- Template Class CameraSubscriber
- Template Class Combiner
- Template Class Divider
- Template Class Filter
- Class FilterBase
- Template Class ImagePublisher
- Template Class ImageSubscriber
- Template Class IO
- Template Class Publisher
- Class PublisherBase
- Template Class Selector
- Template Class Sequencer
- Template Class SimpleUserFilter
- Template Class Sink
- Class Sink::ReentryProtector
- Template Class Source
- Template Class Subscriber
- Class SubscriberBase
- Template Class TfFilter
- Struct TfFilter::Impl
- Struct Impl::MessageInfo
- Struct TfFilter::Impl
- Template Class UserFilter
- Template Class UserSource
- Enum BufferPolicy
- Enum TfFilterResult
- Namespace fkie_message_filters::combiner_policies
- Namespace fkie_message_filters