Template errors creating Approximate Time Synchroniser
Compiler: gcc9.4.0 Arch: Ubuntu20.04/AMD64 ROS Galactic
I'm struggling still to compile a node using an approximate time sync from two topics. I've attempted to closely follow the method used by image_pipeline but even with a few changes to try to solve my issue I'm still stumped on how to get template matching to work correctly here. Help understanding what's going on/wrong here would be appreciated :)
My class is defined as:
namespace pose_eval {
using namespace geometry_msgs::msg;
using namespace sensor_msgs::msg;
using namespace vision_msgs::msg;
using namespace std_msgs::msg;
template <class T>
using Sub = message_filters::Subscriber<T>;
class PoseEval : public rclcpp::Node {
private:
using ApproxPolicy = message_filters::sync_policies::ApproximateTime<Detection2D, PointCloud2>;
using ApproxSync = message_filters::Synchronizer<ApproxPolicy>;
rclcpp::Publisher<PointStamped>::SharedPtr detect_loc_pub_;
std::shared_ptr<ApproxSync> synch_subs_;
message_filters::Subscriber<PointCloud2> pc2_sub_;
message_filters::Subscriber<Detection2D> best_detect_sub_;
void points_callback(const PointCloud2::ConstSharedPtr &points, const Detection2D &best_match);
public:
PoseEval(rclcpp::NodeOptions options);
PoseEval();
~PoseEval();
};
}
And instantiated as:
PoseEval::PoseEval(rclcpp::NodeOptions options) : Node("pose_eval_cpp", options) {
rclcpp::QoS qos = rclcpp::SystemDefaultsQoS();
std::string ns = std::string(this->get_namespace());
this->detect_loc_pub_ = this->create_publisher<PointStamped>(ns + std::string("/"), qos);
pc2_sub_.subscribe(this, ns + "", qos.get_rmw_qos_profile());
best_detect_sub_.subscribe(this, ns + "", qos.get_rmw_qos_profile());
synch_subs_ = std::make_shared<ApproxSync>(
ApproxPolicy(5),
pc2_sub_,
best_detect_sub_);
synch_subs_->registerCallback(std::bind(&PoseEval::points_callback, this, std::placeholders::_1, std::placeholders::_2));
}
The (very verbose) error for that is:
In file included from /opt/ros/galactic/include/message_filters/sync_policies/approximate_time.h:52,
from src/ros2_yolo_cpp/include/ros2_yolo_cpp/pose_eval.hpp:6,
from src/ros2_yolo_cpp/src/pose_eval.cpp:2:
/opt/ros/galactic/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 (pose_eval::PoseEval::*(pose_eval::PoseEval*, std::_Placeholder<1>, std::_Placeholder<2>))(const std::shared_ptr<const sensor_msgs::msg::PointCloud2_<std::allocator<void> > >&, const vision_msgs::msg::Detection2D_<std::allocator<void> >&)>; M0 = vision_msgs::msg::Detection2D_<std::allocator<void> >; M1 = sensor_msgs::msg::PointCloud2_<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/galactic/include/message_filters/synchronizer.h:298:40: required from ‘message_filters::Connection message_filters::Synchronizer<Policy>::registerCallback(const C&) [with C = std::_Bind<void (pose_eval::PoseEval::*(pose_eval::PoseEval*, std::_Placeholder<1>, std::_Placeholder<2>))(const std::shared_ptr<const sensor_msgs::msg::PointCloud2_<std::allocator<void> > >&, const vision_msgs::msg::Detection2D_<std::allocator<void> >&)>; Policy = message_filters::sync_policies::ApproximateTime<vision_msgs::msg::Detection2D_<std::allocator<void> >, sensor_msgs::msg::PointCloud2_<std::allocator<void> > >]’
src/ros2_yolo_cpp/src/pose_eval.cpp:28:128: required from here
/opt/ros/galactic/include/message_filters/signal9.h:280:267: error: no matching function for call to ‘message_filters::Signal9<vision_msgs::msg::Detection2D_<std::allocator<void> >, sensor_msgs::msg::PointCloud2_<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 (pose_eval::PoseEval::*(pose_eval::PoseEval*, std::_Placeholder<1>, std::_Placeholder<2>))(const std::shared_ptr<const sensor_msgs::msg::PointCloud2_<std::allocator<void> > >&, const vision_msgs::msg::Detection2D_<std::allocator<void> >&)>&, const std::_Placeholder<1>&, const std::_Placeholder<2>&, const std::_Placeholder<3>&, const std::_Placeholder<4>&, const ...