Class SubscriberFilter
Defined in File subscriber_filter.hpp
Inheritance Relationships
Base Type
public message_filters::SimpleFilter< sensor_msgs::msg::PointCloud2 >
Class Documentation
-
class SubscriberFilter : public message_filters::SimpleFilter<sensor_msgs::msg::PointCloud2>
PointCloud2 subscription filter.
This class wraps Subscriber as a “filter” compatible with the message_filters package. It acts as a highest-level filter, simply passing messages from a point cloud transport subscription through to the filters which have connected to it.
When this object is destroyed it will unsubscribe from the ROS subscription.
SubscriberFilter has no input connection.
The output connection for the SubscriberFilter object is the same signature as for rclcpp subscription callbacks.
Public Functions
Constructor.
- Parameters:
node – The rclcpp node to use to subscribe.
base_topic – The topic to subscribe to.
queue_size – The subscription queue size
transport – The transport hint to pass along
-
inline POINT_CLOUD_TRANSPORT_PUBLIC SubscriberFilter()
Empty constructor, use subscribe() to subscribe to a topic.
-
inline POINT_CLOUD_TRANSPORT_PUBLIC ~SubscriberFilter()
- inline POINT_CLOUD_TRANSPORT_PUBLIC void subscribe (std::shared_ptr< rclcpp::Node > node, const std::string &base_topic, const std::string &transport, rmw_qos_profile_t custom_qos=rmw_qos_profile_default, rclcpp::SubscriptionOptions options=rclcpp::SubscriptionOptions())
Subscribe to a topic. If this Subscriber is already subscribed to a topic, this function will first unsubscribe.
- Parameters:
node – The rclcpp Node to use to subscribe.
base_topic – The topic to subscribe to.
transport – The transport hint to pass along
custom_qos – Custom quality of service
options – Subscriber options
- inline POINT_CLOUD_TRANSPORT_PUBLIC void unsubscribe ()
Force immediate unsubscription of this subscriber from its topic.
- inline POINT_CLOUD_TRANSPORT_PUBLIC std::string getTopic () const
- inline POINT_CLOUD_TRANSPORT_PUBLIC uint32_t getNumPublishers () const
Returns the number of publishers this subscriber is connected to.
- inline POINT_CLOUD_TRANSPORT_PUBLIC std::string getTransport () const
Returns the name of the transport being used.
- inline POINT_CLOUD_TRANSPORT_PUBLIC const Subscriber & getSubscriber () const
Returns the internal point_cloud_transport::Subscriber object.