Template Class SubscriberBase

Class Documentation

template<class NodeType = rclcpp::Node>
class SubscriberBase

Public Types

typedef std::shared_ptr<NodeType> NodePtr

Public Functions

virtual ~SubscriberBase() = default
virtual void subscribe(NodePtr node, const std::string &topic, const rmw_qos_profile_t qos = rmw_qos_profile_default) = 0

Subscribe to a topic.

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

Parameters:
  • node – The rclcpp::Node::SharedPtr to use to subscribe.

  • topic – The topic to subscribe to.

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

virtual void subscribe(NodeType *node, const std::string &topic, const rmw_qos_profile_t qos = rmw_qos_profile_default) = 0

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.

  • topic – The topic to subscribe to.

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

inline virtual void subscribe(NodePtr node, const std::string &topic, const rmw_qos_profile_t qos, rclcpp::SubscriptionOptions options)

Subscribe to a topic.

If this Subscriber is already subscribed to a topic, this function will first unsubscribe. This override allows SubscriptionOptions to be passed into the class without changing API.

Parameters:
  • node – The rclcpp::Node::SharedPtr to use to subscribe.

  • topic – The topic to subscribe to.

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

  • options – The subscription options to use to subscribe.

inline virtual void subscribe(NodeType *node, const std::string &topic, const rmw_qos_profile_t qos, rclcpp::SubscriptionOptions options)

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.

  • topic – The topic to subscribe to.

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

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.