Skip to content
Original file line number Diff line number Diff line change
Expand Up @@ -36,12 +36,13 @@
#include <string>

#include <rclcpp/rclcpp.hpp>
#include <message_filters/simple_filter.hpp> // NOLINT
#include <message_filters/subscriber.hpp>
#include <sensor_msgs/msg/point_cloud2.hpp>

#include <point_cloud_transport/point_cloud_transport.hpp>
#include <point_cloud_transport/transport_hints.hpp>
#include "point_cloud_transport/visibility_control.hpp"
#include "point_cloud_transport/exception.hpp"

namespace point_cloud_transport
{
Expand All @@ -60,7 +61,9 @@ namespace point_cloud_transport
/// The output connection for the SubscriberFilter object is the same signature as for rclcpp
/// subscription callbacks.
///
class SubscriberFilter : public message_filters::SimpleFilter<sensor_msgs::msg::PointCloud2>
class SubscriberFilter
: public message_filters::SubscriberBase,
public message_filters::SimpleFilter<sensor_msgs::msg::PointCloud2>
{
public:
///
Expand Down Expand Up @@ -89,7 +92,9 @@ class SubscriberFilter : public message_filters::SimpleFilter<sensor_msgs::msg::
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface> node_interfaces,
const std::string & base_topic,
const std::string & transport);
const std::string & transport,
rclcpp::QoS custom_qos = rclcpp::SystemDefaultsQoS(),
rclcpp::SubscriptionOptions options = rclcpp::SubscriptionOptions());

//! Empty constructor, use subscribe() to subscribe to a topic
POINT_CLOUD_TRANSPORT_PUBLIC
Expand Down Expand Up @@ -140,9 +145,14 @@ class SubscriberFilter : public message_filters::SimpleFilter<sensor_msgs::msg::
rclcpp::QoS custom_qos,
rclcpp::SubscriptionOptions options = rclcpp::SubscriptionOptions());

//! Re-subscribe to a topic.
// Only works if this subscriber has previously been subscribed to a topic.
POINT_CLOUD_TRANSPORT_PUBLIC
void subscribe() override;

//! Force immediate unsubscription of this subscriber from its topic
POINT_CLOUD_TRANSPORT_PUBLIC
void unsubscribe();
void unsubscribe() override;

POINT_CLOUD_TRANSPORT_PUBLIC
std::string getTopic() const;
Expand All @@ -160,12 +170,47 @@ class SubscriberFilter : public message_filters::SimpleFilter<sensor_msgs::msg::
const Subscriber & getSubscriber() const;

private:
//! Must override parent message_filters::SubscriberBase method
// where RequiredInterfaces are just <NodeParametersInterface, NodeTopicsInterface>
void subscribe(
Copy link
Member

@SteveMacenski SteveMacenski Jun 27, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Then remove if it shouldn't be used? 😆

Copy link
Contributor Author

@elsayedelsheikh elsayedelsheikh Jun 28, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

  • About inheriting from SubscriberBase , We need to override these 2 functions but our subscriber needs more node_interfaces so I left them empty and shouldn't be used
      void subscribe(
        RequiredInterfaces /*node_interfaces*/, const std::string & /*topic*/,
        const rclcpp::QoS & /*qos*/) override
      {}
      void subscribe(
        RequiredInterfaces  /*node_interfaces*/,
        const std::string & /*topic*/,
        const rclcpp::QoS & /*qos*/,
        rclcpp::SubscriptionOptions /*options*/) override
      {}

Won't be able to create a class object if not implemented, Check this
So that I put them under private so no one uses them :D

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Ugh. I think that should be reverted too with the subscribe function similarly templated by NodeT that can be auto-deduced. Before I think it was a pain because the entire class was templated rather than just the method that can autodeduce the type from the arguments.

@ahcorde what do you think?

Copy link
Member

@SteveMacenski SteveMacenski Jul 1, 2025

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Exposing the RequiredInterfaces to the application code is super nasty and can be populated internally to the message filter from the argument provided NodeT. I think merging this in March was not the best solution ros2/message_filters#113. Using RequiredInterfaces as an input if the method is templated will still work as a NodeT as long as it provides the same get_X_base_interface() method. That appears to be the case https://github.com/ros2/rclcpp/blob/rolling/rclcpp/include/rclcpp/node_interfaces/node_interfaces.hpp#L108-L110

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

This is very nice documented issue ros2/geometry2#698 why we shouldn't use templates and why we should use rclcpp::node_interfaces::NodeInterfaces

There is a ppt too https://docs.google.com/presentation/d/1bdXOOZPhR9yAnyGNxoLhuO_bU4RW5IjnzvCtrVlpe_g/edit?slide=id.g24afec4abf4_0_0#slide=id.g24afec4abf4_0_0

Maybe we can still improve something in message filter, but I prefer rclcpp::node_interfaces::NodeInterfaces instead of NodeT

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Would we need to update message filters too?

Copy link
Contributor Author

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

I think I'm lost here... 🤔
So you guys are proposing to use f(*NodeT) for implicit conversion to node_interfaces, similar to
https://github.com/ros2/message_filters/blob/4f17c17813e7b84e34cc287143ddf70471c78d6c/include/message_filters/subscriber.hpp#L168-L173

Then, Would it be ok to leave SubscriberBase pure virtual methods under private without implementation { }?

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Let me create the PR with my suggestions, and we can move forward from there

Copy link
Collaborator

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

Here my suggestions #129 @SteveMacenski @elsayedelsheikh

Copy link
Member

Choose a reason for hiding this comment

The reason will be displayed to describe this comment to others. Learn more.

That looks good to me! I think after rebasing onto that, whatever changes are still required for aligning with message filters are still related but simplifies things quite a bit in the best ways.

Just to check, all this works with a rclcpp_lifecycle::LifecycleNode or even a nav2::LifecycleNode in auto-populating that interfaces objcet, correct? All the docs make me think that's the case, but just verifying since I still see the specialized rclcpp::Node constructors in your PR. Couldn't those be removed?

rclcpp::node_interfaces::NodeInterfaces<
NodeParametersInterface,
NodeTopicsInterface>,
const std::string &,
const rclcpp::QoS &) override
{
throw point_cloud_transport::Exception("Not implemented");
}

//! Must override parent message_filters::SubscriberBase method
// where RequiredInterfaces are just <NodeParametersInterface, NodeTopicsInterface>
void subscribe(
rclcpp::node_interfaces::NodeInterfaces<
NodeParametersInterface,
NodeTopicsInterface>,
const std::string &,
const rclcpp::QoS &,
rclcpp::SubscriptionOptions) override
{
throw point_cloud_transport::Exception("Not implemented");
}

void cb(const sensor_msgs::msg::PointCloud2::ConstSharedPtr & m)
{
signalMessage(m);
}

Subscriber sub_;
rclcpp::node_interfaces::NodeInterfaces<
rclcpp::node_interfaces::NodeBaseInterface,
rclcpp::node_interfaces::NodeParametersInterface,
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface> node_interfaces_;

std::string topic_;
std::string transport_;
rclcpp::QoS qos_ = rclcpp::SystemDefaultsQoS();
rclcpp::SubscriptionOptions options_;
};

} // namespace point_cloud_transport
Expand Down
41 changes: 30 additions & 11 deletions point_cloud_transport/src/subscriber_filter.cpp
Original file line number Diff line number Diff line change
Expand Up @@ -28,6 +28,7 @@

#include "point_cloud_transport/subscriber_filter.hpp"

#include <functional>
#include <memory>
#include <string>

Expand All @@ -40,9 +41,11 @@ SubscriberFilter::SubscriberFilter(
rclcpp::node_interfaces::NodeTopicsInterface,
rclcpp::node_interfaces::NodeLoggingInterface> node_interfaces,
const std::string & base_topic,
const std::string & transport)
const std::string & transport,
rclcpp::QoS custom_qos,
rclcpp::SubscriptionOptions options)
{
subscribe(node_interfaces, base_topic, transport, rclcpp::SystemDefaultsQoS());
subscribe(node_interfaces, base_topic, transport, custom_qos, options);
}

SubscriberFilter::SubscriberFilter()
Expand All @@ -61,13 +64,8 @@ void SubscriberFilter::subscribe(
rmw_qos_profile_t custom_qos,
rclcpp::SubscriptionOptions options)
{
unsubscribe();
sub_ = point_cloud_transport::create_subscription(
*node, base_topic,
std::bind(&SubscriberFilter::cb, this, std::placeholders::_1),
transport,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(custom_qos), custom_qos),
options);
subscribe(*node, base_topic, transport,
rclcpp::QoS(rclcpp::QoSInitialization::from_rmw(custom_qos), custom_qos), options);
}

void SubscriberFilter::subscribe(
Expand Down Expand Up @@ -101,6 +99,27 @@ void SubscriberFilter::subscribe(
node_interfaces, base_topic,
std::bind(&SubscriberFilter::cb, this, std::placeholders::_1),
transport, custom_qos, options);
node_interfaces_ = node_interfaces;
topic_ = base_topic;
transport_ = transport;
qos_ = custom_qos;
options_ = options;
}

void SubscriberFilter::subscribe()
{
unsubscribe();
if (!topic_.empty()) {
sub_ = point_cloud_transport::create_subscription(
node_interfaces_, topic_,
std::bind(&SubscriberFilter::cb, this, std::placeholders::_1),
transport_, qos_, options_);
} else {
RCLCPP_ERROR(
node_interfaces_.get_node_logging_interface()->get_logger(),
"Cannot re-subscribe: the subscriber filter must be initialized first."
);
}
}

void SubscriberFilter::unsubscribe()
Expand All @@ -110,7 +129,7 @@ void SubscriberFilter::unsubscribe()

std::string SubscriberFilter::getTopic() const
{
return sub_.getTopic();
return this->topic_;
}

uint32_t SubscriberFilter::getNumPublishers() const
Expand All @@ -120,7 +139,7 @@ uint32_t SubscriberFilter::getNumPublishers() const

std::string SubscriberFilter::getTransport() const
{
return sub_.getTransport();
return this->transport_;
}

const Subscriber & SubscriberFilter::getSubscriber() const
Expand Down