Subscription and Message Filters Demo
Introduction
In this tutorial, we first present how to create a simple subscribers in C++ and then we'll explore message filters, an useful tool to combine multiple streams of messages.
Related Readings
Create a simple subscriber
Creating subscribers in ROS2 is a relatively simple process that requires specifying a topic and a callback function. Typically, this callback function is a member function of a node. To adapt a member function into a function reference suitable for the subscriber, we can employ techniques such as std::bind
or a lambda function. For instance:
subscription1_ = this->create_subscription<std_msgs::msg::String>(
"/robot_1/published_message", 3, std::bind(&BasicSubscriber::callback_1, this, _1));
subscription2_ = this->create_subscription<std_msgs::msg::String>(
"/robot_2/published_message", 3, [this](const std_msgs::msg::String & msg) {this->callback_2(msg);});
void callback_1(const std_msgs::msg::String & msg);
void callback_2(const std_msgs::msg::String & msg)
While CLion suggests using the lambda function format, the choice ultimately boils down to personal preference. It's important to note that the callback function can accept the message reference as its argument.
Use message filter
A message filter can be viewed as a function applied to one or more incoming message streams and generates an output message stream. The message_filters
package in ROS2 provides tools such as the Subscriber
class and policy-based Synchronizer
class to streamline the process of combining message streams. The following code snippet illustrates the creation and application of a message filter using the approximate time synchronizer. An illustration of the synchronization algorithm can be found at this link.
using DataType = std_msgs::msg::String;
using MySyncPolicy = message_filters::sync_policies::ApproximateTime<DataType, DataType>;
subscriber1_ = std::make_unique<message_filters::Subscriber<DataType>>(this, "/robot_1/published_message");
subscriber2_ = std::make_unique<message_filters::Subscriber<DataType>>(this, "/robot_2/published_message");
sync_ = std::make_unique<message_filters::Synchronizer<MySyncPolicy>>(MySyncPolicy(10), *subscriber1_, *subscriber2_);
sync_->registerCallback(std::bind(&BasicSubscriber::callback_synchronizer, this, _1, _2));
void callback_synchronizer(const std_msgs::msg::String::ConstSharedPtr& msg1, const std_msgs::msg::String::ConstSharedPtr& msg2)
It's important to note that the callback accepts the pointer of the message as its argument.
Demo setup
In the demo code, we will set up
Two publisher nodes. Each of these publishers emits a string message at a fixed rate.The first publisher does so every second, while the second publisher sends out its message every three seconds.
A subscriber node. The subscriber node subscribes to the topics using two different method. The first method involves the standard subscription created from the node. Custom callback functions are detailed in the demo code, showcasing synchronization techniques. The second method uses the
message_filters::Subscriber
class and pass the two message streams to an approximate time synchronizer. A callback function that outputs the synced message pairs is attached to the filter.A launch file is included to launch the system.
Result
The code produces the following results:
[INFO] [1703180455.850472669] [minimal_subscriber]: Synced message: Hello, world! 0 | Hello, world! 0
[INFO] [1703180458.849553854] [minimal_subscriber]: Report count 5
[INFO] [1703180458.849662810] [minimal_subscriber]: Synced message: Hello, world! 1 | Hello, world! 1
[INFO] [1703180461.850195260] [minimal_subscriber]: Synced message: Hello, world! 2 | Hello, world! 2
[INFO] [1703180464.849931543] [minimal_subscriber]: Report count 6
[INFO] [1703180464.850334020] [minimal_subscriber]: Synced message: Hello, world! 3 | Hello, world! 3
[INFO] [1703180467.850195856] [minimal_subscriber]: Synced message: Hello, world! 4 | Hello, world! 4
[INFO] [1703180470.850082954] [minimal_subscriber]: Report count 6
[INFO] [1703180470.850464750] [minimal_subscriber]: Synced message: Hello, world! 7 | Hello, world! 5
[INFO] [1703180473.850209145] [minimal_subscriber]: Synced message: Hello, world! 10 | Hello, world! 6
[INFO] [1703180476.850447058] [minimal_subscriber]: Synced message: Hello, world! 13 | Hello, world! 7
[INFO] [1703180479.850429622] [minimal_subscriber]: Synced message: Hello, world! 16 | Hello, world! 8
[INFO] [1703180482.850377697] [minimal_subscriber]: Report count 12
[INFO] [1703180482.850753011] [minimal_subscriber]: Synced message: Hello, world! 19 | Hello, world! 9
[INFO] [1703180485.850230340] [minimal_subscriber]: Synced message: Hello, world! 22 | Hello, world! 10
[INFO] [1703180488.850340054] [minimal_subscriber]: Report count 6
[INFO] [1703180488.850797899] [minimal_subscriber]: Synced message: Hello, world! 25 | Hello, world! 11
[INFO] [1703180491.850552337] [minimal_subscriber]: Synced message: Hello, world! 28 | Hello, world! 12
[INFO] [1703180494.850307471] [minimal_subscriber]: Synced message: Hello, world! 31 | Hello, world! 13
[INFO] [1703180497.850698574] [minimal_subscriber]: Synced message: Hello, world! 34 | Hello, world! 14
[INFO] [1703180500.850442515] [minimal_subscriber]: Synced message: Hello, world! 37 | Hello, world! 15
[INFO] [1703180503.850877867] [minimal_subscriber]: Synced message: Hello, world! 40 | Hello, world! 16
We make two observations:
There are no gaps in the messages from the publisher 2 because the messages are published at a slower rate.
Once the system stabilizes, the gaps in the printed message from the publisher 1 consistently stay at 3.
Download code
The code is available for download at this link.
Β©2023 - 2024 all rights reserved
Last updated