ROS2 message_filters Synchronizer compilation error
Hi, I am having trouble compiling my code using the message_filters Synchronizer in ROS2 Foxy. The tests included in the library compile and run fine but the code below does not want to compile on multiple systems with the following configurations:
OS: Ubuntu 20.04
Distro: ROS2 Foxy
message_filters: 3.2.5 (apt version)
My code:
#include <rclcpp/rclcpp.hpp>
#include <std_msgs/msg/string.hpp>
#include <message_filters/subscriber.h>
#include <message_filters/sync_policies/approximate_time.h>
#include <message_filters/sync_policies/exact_time.h>
#include <message_filters/synchronizer.h>
using namespace std::placeholders;
class SyncNode : rclcpp::Node{
private:
using approximate_policy = message_filters::sync_policies::ApproximateTime<std_msgs::msg::String, std_msgs::msg::String>;
typedef message_filters::Synchronizer<approximate_policy> Synchronizer;
message_filters::Subscriber<std_msgs::msg::String> sub1;
message_filters::Subscriber<std_msgs::msg::String> sub2;
std::unique_ptr<Synchronizer> sync;
void callback(const std_msgs::msg::String::SharedPtr msg1, const std_msgs::msg::String::SharedPtr msg2);
public:
SyncNode() : Node("test_message_filters_node"){
sub1.subscribe(this, "/message_1");
sub2.subscribe(this, "/message_2");
sync.reset(new message_filters::Synchronizer<approximate_policy>(approximate_policy(10), sub1, sub2));
sync->registerCallback(std::bind(&SyncNode::callback, this, _1, _2));
}
};
void SyncNode::callback(const std_msgs::msg::String::SharedPtr msg1, const std_msgs::msg::String::SharedPtr msg2){
RCLCPP_INFO(this->get_logger(), "Messages synced: Callback activated"); }
Compiling with GCC and G++ 9.4, I get the following error:
In file included from /opt/ros/foxy/include/message_filters/sync_policies/approximate_time.h:52,
from /home/benjamin/Documents/Mechatronics/ros2/dev_ws/src/test_message_filters/include/test_message_filters/msg_node.hpp:4,
from /home/benjamin/Documents/Mechatronics/ros2/dev_ws/src/test_message_filters/src/test_sync.cpp:3:
/opt/ros/foxy/include/message_filters/signal9.h: In instantiation of ‘message_filters::Connection message_filters::Signal9<M0, M1, M2, M3, M4, M5, M6, M7, M8>::addCallback(C&) [with C = const std::_Bind<void (SyncNode::*(SyncNode*, std::_Placeholder<1>, std::_Placeholder<2>))(std::shared_ptr<std_msgs::msg::String_<std::allocator<void> > >, std::shared_ptr<std_msgs::msg::String_<std::allocator<void> > >)>; M0 = std_msgs::msg::String_<std::allocator<void> >; M1 = std_msgs::msg::String_<std::allocator<void> >; M2 = message_filters::NullType; M3 = message_filters::NullType; M4 = message_filters::NullType; M5 = message_filters::NullType; M6 = message_filters::NullType; M7 = message_filters::NullType; M8 = message_filters::NullType]’:
/opt/ros/foxy/include/message_filters/synchronizer.h:298:40: required from ‘message_filters::Connection message_filters::Synchronizer<Policy>::registerCallback(const C&) [with C = std::_Bind<void (SyncNode::*(SyncNode*, std::_Placeholder<1>, std::_Placeholder<2>))(std::shared_ptr<std_msgs::msg::String_<std::allocator<void> > >, std::shared_ptr<std_msgs::msg::String_<std::allocator<void> > >)>; Policy = message_filters::sync_policies::ApproximateTime<std_msgs::msg::String_<std::allocator<void> >, std_msgs::msg::String_<std::allocator<void> > >]’
/home/benjamin/Documents/Mechatronics/ros2/dev_ws/src/test_message_filters/include/test_message_filters/msg_node.hpp:32:76: required from here
/opt/ros/foxy/include/message_filters/signal9.h:280:267: error: no matching function for call to ‘message_filters::Signal9<std_msgs::msg::String_<std::allocator<void> >, std_msgs::msg::String_<std::allocator<void> >, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType, message_filters::NullType>::addCallback<const M0ConstPtr&, const M1ConstPtr&, const M2ConstPtr&, const M3ConstPtr&, const M4ConstPtr&, const M5ConstPtr&, const M6ConstPtr&, const M7ConstPtr&, const M8ConstPtr&>(std::_Bind_helper<false, const std::_Bind<void (SyncNode::*(SyncNode*, std::_Placeholder<1>, std::_Placeholder<2>))(std::shared_ptr<std_msgs::msg::String_<std::allocator<void> > >, std::shared_ptr<std_msgs::msg::String_<std::allocator<void> > >)>&, const std::_Placeholder<1>&, const std::_Placeholder<2>&, const std::_Placeholder<3>&, const std::_Placeholder<4>&, const std::_Placeholder<5>&, const std::_Placeholder<6>&, const std::_Placeholder<7>&, const std ...