Template Class SubscriberBase

Class Documentation

template<class NodeType = DeprecatedTemplateParameter>
class SubscriberBase

Public Types

typedef std::shared_ptr<NodeType> NodePtr
using NodeParametersInterface = rclcpp::node_interfaces::NodeParametersInterface
using NodeTopicsInterface = rclcpp::node_interfaces::NodeTopicsInterface
using RequiredInterfaces = rclcpp::node_interfaces::NodeInterfaces<NodeParametersInterface, NodeTopicsInterface>

Public Functions

template<typename U = NodeType, std::enable_if_t<std::is_same<U, DeprecatedTemplateParameter>{}, int> = 0>
inline SubscriberBase()
template<typename U = NodeType, std::enable_if_t<!std::is_same<U, DeprecatedTemplateParameter>{}, int> = 0>
inline SubscriberBase()
virtual ~SubscriberBase() = default
virtual void subscribe(RequiredInterfaces node_interfaces, const std::string &topic, const rclcpp::QoS &qos) = 0

Subscribe to a topic.

If this Subscriber is already subscribed to a topic, this function will first unsubscribe.

Parameters:
  • node_interfaces – The NodeInterfaces to use to subscribe.

  • topic – The topic to subscribe to.

  • qos – (optional) The rmw qos profile to use to subscribe

virtual void subscribe(RequiredInterfaces node_interfaces, const std::string &topic, const rclcpp::QoS &qos, rclcpp::SubscriptionOptions options) = 0

Subscribe to a topic.

If this Subscriber is already subscribed to a topic, this function will first unsubscribe.

Parameters:
  • node_interfaces – 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.

inline virtual void subscribe(NodePtr node, const std::string &topic, const rclcpp::QoS &qos)
inline virtual void subscribe(NodeType *node, const std::string &topic, const rclcpp::QoS &qos)
inline virtual void subscribe(RequiredInterfaces node_interfaces, const std::string &topic, const rmw_qos_profile_t qos)
inline virtual void subscribe(NodePtr node, const std::string &topic, const rmw_qos_profile_t qos)
inline virtual void subscribe(NodeType *node, const std::string &topic, const rmw_qos_profile_t qos)
inline virtual void subscribe(NodePtr node, const std::string &topic, const rclcpp::QoS &qos, rclcpp::SubscriptionOptions options)
inline virtual void subscribe(NodeType *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, rclcpp::SubscriptionOptions options)
inline virtual void subscribe(NodePtr node, const std::string &topic, const rmw_qos_profile_t qos, rclcpp::SubscriptionOptions options)
inline virtual void subscribe(NodeType *node, const std::string &topic, const rmw_qos_profile_t qos, rclcpp::SubscriptionOptions options)
virtual void subscribe() = 0

Re-subscribe to a topic. Only works if this subscriber has previously been subscribed to a topic.

virtual void unsubscribe() = 0

Force immediate unsubscription of this subscriber from its topic.