Template Class Subscriber

Inheritance Relationships

Base Types

Class Documentation

template<class M, class NodeType = rclcpp::Node>
class Subscriber : public message_filters::SubscriberBase<rclcpp::Node>, public message_filters::SimpleFilter<message_type_t<M>>

Public Types

typedef std::shared_ptr<NodeType> NodePtr
typedef message_type_t<M> MessageType
typedef MessageEvent<MessageType const> EventType

Public Functions

inline Subscriber(NodePtr node, const std::string &topic, const rmw_qos_profile_t qos = rmw_qos_profile_default)

Constructor.

See the rclcpp::Node::subscribe() variants for more information on the parameters

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

inline Subscriber(NodeType *node, const std::string &topic, const rmw_qos_profile_t qos = rmw_qos_profile_default)
inline Subscriber(NodePtr node, 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 rclcpp::Node::SharedPtr 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 Subscriber(NodeType *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 void subscribe(NodePtr node, 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 rclcpp::Node::SharedPtr to use to subscribe.

  • topic – The topic to subscribe to.

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

inline void subscribe(NodeType *node, 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 rclcpp::Node to use to subscribe.

  • topic – The topic to subscribe to.

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

inline void subscribe(NodePtr node, 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 rclcpp::Node::SharedPtr 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 void subscribe(NodeType *node, 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 rclcpp::Node 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() 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.