Template Class Subscriber
Defined in File subscriber.hpp
Inheritance Relationships
Base Types
public message_filters::SubscriberBase< DeprecatedTemplateParameter >(Template Class SubscriberBase)public message_filters::SimpleFilter< message_type_t< M > >(Template Class SimpleFilter)
Class Documentation
-
template<class M, class NodeType = DeprecatedTemplateParameter>
class Subscriber : public message_filters::SubscriberBase<DeprecatedTemplateParameter>, public message_filters::SimpleFilter<message_type_t<M>> Public Types
-
typedef message_type_t<M> MessageType
-
typedef MessageEvent<MessageType const> EventType
-
using RequiredInterfaces = typename SubscriberBase<NodeType>::RequiredInterfaces
-
using NodeParametersInterface = typename SubscriberBase<NodeType>::NodeParametersInterface
-
using NodeTopicsInterface = typename SubscriberBase<NodeType>::NodeTopicsInterface
Public Functions
-
template<typename U = NodeType, std::enable_if_t<!std::is_same<U, DeprecatedTemplateParameter>{}, int> = 0>
inline Subscriber(RequiredInterfaces node_interfaces, const std::string &topic, const rclcpp::QoS &qos, rclcpp::SubscriptionOptions options) Solely for highlighting deprecated template parameters with a compiler warning.
-
template<typename U = NodeType, std::enable_if_t<!std::is_same<U, DeprecatedTemplateParameter>{}, int> = 0>
inline Subscriber(RequiredInterfaces node_interfaces, const std::string &topic, const rclcpp::QoS &qos) Solely for highlighting deprecated template parameters with a compiler warning.
-
template<typename U = NodeType, std::enable_if_t<std::is_same<U, DeprecatedTemplateParameter>{}, int> = 0>
inline Subscriber(RequiredInterfaces node_interfaces, const std::string &topic, const rclcpp::QoS &qos) Constructor.
See the rclcpp::Node::subscribe() variants for more information on the parameters
- Parameters:
node – The NodeInterfaces to use to subscribe.
topic – The topic to subscribe to.
qos – (optional) The rmw qos profile to use to subscribe
-
template<typename NodeT>
inline Subscriber(NodeT *node, const std::string &topic, const rclcpp::QoS &qos)
-
template<typename U = NodeType, std::enable_if_t<std::is_same<U, DeprecatedTemplateParameter>{}, int> = 0>
inline Subscriber(RequiredInterfaces node_interfaces, const std::string &topic, const rclcpp::QoS &qos, rclcpp::SubscriptionOptions options) Constructor.
See the rclcpp::Node::subscribe() variants for more information on the parameters
- Parameters:
node – The NodeInterfaces to use to subscribe.
topic – The topic to subscribe to.
qos – The rmw qos profile to use to subscribe.
options – The subscription options to use to subscribe.
-
template<typename NodeT>
inline Subscriber(NodeT *node, const std::string &topic, const rclcpp::QoS &qos, rclcpp::SubscriptionOptions options)
-
inline Subscriber(RequiredInterfaces node_interfaces, const std::string &topic, const rmw_qos_profile_t qos = rmw_qos_profile_default)
-
template<typename NodeT>
inline Subscriber(NodeT *node, const std::string &topic, const rmw_qos_profile_t qos = rmw_qos_profile_default)
-
inline Subscriber(RequiredInterfaces node_interfaces, const std::string &topic, const rmw_qos_profile_t qos, rclcpp::SubscriptionOptions options)
Constructor.
See the rclcpp::Node::subscribe() variants for more information on the parameters
- Parameters:
node – The NodeInterfaces to use to subscribe.
topic – The topic to subscribe to.
qos – The rmw qos profile to use to subscribe.
options – The subscription options to use to subscribe.
-
template<typename NodeT>
inline Subscriber(NodeT *node, const std::string &topic, const rmw_qos_profile_t qos, rclcpp::SubscriptionOptions options)
-
Subscriber() = default
Empty constructor, use subscribe() to subscribe to a topic.
-
inline ~Subscriber()
-
inline virtual void subscribe(RequiredInterfaces node_interfaces, const std::string &topic, const rclcpp::QoS &qos) override
Subscribe to a topic.
If this Subscriber is already subscribed to a topic, this function will first unsubscribe.
- Parameters:
node – The NodeInterfaces to use to subscribe.
topic – The topic to subscribe to.
qos – (optional) The rmw qos profile to use to subscribe
-
template<typename NodeT>
inline void subscribe(NodeT *node, const std::string &topic, const rclcpp::QoS &qos)
-
inline virtual void subscribe(RequiredInterfaces node_interfaces, const std::string &topic, const rclcpp::QoS &qos, rclcpp::SubscriptionOptions options) override
Subscribe to a topic.
If this Subscriber is already subscribed to a topic, this function will first unsubscribe.
- Parameters:
node – The NodeInterfaces to use to subscribe.
topic – The topic to subscribe to.
qos – The rmw qos profile to use to subscribe.
options – The subscription options to use to subscribe.
-
template<typename NodeT>
inline void subscribe(NodeT *node, const std::string &topic, const rclcpp::QoS &qos, rclcpp::SubscriptionOptions options)
-
inline virtual void subscribe(RequiredInterfaces node_interfaces, const std::string &topic, const rmw_qos_profile_t qos = rmw_qos_profile_default) override
Subscribe to a topic.
If this Subscriber is already subscribed to a topic, this function will first unsubscribe.
- Parameters:
node – The NodeInterfaces to use to subscribe.
topic – The topic to subscribe to.
qos – (optional) The rmw qos profile to use to subscribe
-
template<typename NodeT>
inline void subscribe(NodeT *node, const std::string &topic, const rmw_qos_profile_t qos = rmw_qos_profile_default)
-
inline virtual void subscribe(RequiredInterfaces node_interfaces, const std::string &topic, const rmw_qos_profile_t qos, rclcpp::SubscriptionOptions options) override
Subscribe to a topic.
If this Subscriber is already subscribed to a topic, this function will first unsubscribe.
- Parameters:
node – The NodeInterfaces to use to subscribe.
topic – The topic to subscribe to.
qos – The rmw qos profile to use to subscribe.
options – The subscription options to use to subscribe.
-
template<typename NodeT>
inline void subscribe(NodeT *node, const std::string &topic, const rmw_qos_profile_t qos, rclcpp::SubscriptionOptions options)
-
inline virtual void subscribe() override
Re-subscribe to a topic. Only works if this subscriber has previously been subscribed to a topic.
-
inline virtual void unsubscribe() override
Force immediate unsubscription of this subscriber from its topic.
-
inline std::string getTopic() const
-
inline const rclcpp::Subscription<M>::SharedPtr getSubscriber() const
Returns the internal rclcpp::Subscription<M>::SharedPtr object.
-
template<typename F>
inline void connectInput(F &f) Does nothing. Provided so that Subscriber may be used in a message_filters::Chain.
-
inline void add(const EventType &e)
Does nothing. Provided so that Subscriber may be used in a message_filters::Chain.
-
typedef message_type_t<M> MessageType