Subscribe to a ROS topic as data provider. More...
#include <subscriber.h>
Public Member Functions | |
void | set_subscribe_options (ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=nullptr) noexcept |
Configure ROS topic that is to be subscribed. More... | |
void | subscribe (ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=nullptr) noexcept |
Convenience function to subscribe to a ROS topic. More... | |
Subscriber () noexcept | |
Constructs an empty subscriber. More... | |
Subscriber (ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=nullptr) noexcept | |
Constructor that subscribes to the given ROS topic. More... | |
virtual std::string | topic () const noexcept override |
Return the subscribed topic name. More... | |
Protected Member Functions | |
virtual bool | is_configured () const noexcept override |
Check if the ROS subscriber is properly configured. More... | |
virtual void | subscribe_impl () noexcept override |
Create a ROS subscriber. More... | |
virtual void | unsubscribe_impl () noexcept override |
Shut the ROS subscriber down. More... | |
Private Types | |
using | EventType = typename Translate< M >::EventType |
using | FilterType = typename Translate< M >::FilterType |
Private Member Functions | |
void | cb (const EventType &event) |
Private Attributes | |
std::shared_ptr< ros::NodeHandle > | nh_ |
ros::SubscribeOptions | opts_ |
ros::Subscriber | sub_ |
Additional Inherited Members |
Subscribe to a ROS topic as data provider.
This class together with the Publisher class is the generic interface between ROS and this library. All messages which are received on the subscribed topic will be passed to the connected sinks for further processing. For maximum flexibility, you can choose one of four ways how to pass the received message:
Subscriber<M, RosMessageEvent>
will act as a source of ros::MessageEvent<const M>
objects (default) Subscriber<M, RosMessageConstPtr>
will act as a source of M::ConstPtr
objects (as of this writing, this is a boost::shared_ptr<const M>
) Subscriber<M, RosMessageStdSharedPtr>
will act as a source of std::shared_ptr<const M>
objects Subscriber<M, RosMessage>
will act as a source of plain M
objectsUnlike regular ROS subscribers, this class can be associated with a publisher instance. In that case, the subscriber will delay subscription until the publisher is actively used and will unsubscribe (and stop passing data) as soon as the publisher becomes idle. This is a convenient method to save processing power if the filter pipeline is used only intermittently.
Definition at line 54 of file subscriber.h.
|
private |
Definition at line 125 of file subscriber.h.
|
private |
Definition at line 126 of file subscriber.h.
|
noexcept |
Constructs an empty subscriber.
You need to call set_subscribe_options() and either subscribe() or subscribe_on_demand() to actually subscribe to a ROS topic.
Definition at line 29 of file subscriber_impl.h.
|
noexcept |
Constructor that subscribes to the given ROS topic.
This constructor calls set_subscribe_options() and subscribe() for you.
nh
ROS node handle to create the ROS subscription topic
name of the ROS topic, subject to remapping queue_size
size of the ROS subscription queue transport_hints
low-level transport hints for the ROS client library callback_queue
custom ROS callback queueDefinition at line 34 of file subscriber_impl.h.
|
private |
Definition at line 88 of file subscriber_impl.h.
|
overrideprotectedvirtualnoexcept |
Check if the ROS subscriber is properly configured.
Implements fkie_message_filters::SubscriberBase.
Definition at line 67 of file subscriber_impl.h.
|
noexcept |
Configure ROS topic that is to be subscribed.
All arguments are passed to the ROS client library; see the ROS documentation for further information. Calling this method will automatically unsubscribe any previously subscribed ROS topic.
nh
ROS node handle to create the ROS subscription topic
name of the ROS topic, subject to remapping queue_size
size of the ROS subscription queue transport_hints
low-level transport hints for the ROS client library callback_queue
custom ROS callback queueDefinition at line 46 of file subscriber_impl.h.
|
noexcept |
Convenience function to subscribe to a ROS topic.
This function is equivalent to calling set_subscribe_options() and then subscribe().
nh
ROS node handle to create the ROS subscription topic
name of the ROS topic, subject to remapping queue_size
size of the ROS subscription queue transport_hints
low-level transport hints for the ROS client library callback_queue
custom ROS callback queueDefinition at line 59 of file subscriber_impl.h.
|
overrideprotectedvirtualnoexcept |
Create a ROS subscriber.
Implements fkie_message_filters::SubscriberBase.
Definition at line 73 of file subscriber_impl.h.
|
overridevirtualnoexcept |
Return the subscribed topic name.
Implements fkie_message_filters::SubscriberBase.
Definition at line 40 of file subscriber_impl.h.
|
overrideprotectedvirtualnoexcept |
Shut the ROS subscriber down.
Implements fkie_message_filters::SubscriberBase.
Definition at line 82 of file subscriber_impl.h.
|
private |
Definition at line 130 of file subscriber.h.
|
private |
Definition at line 129 of file subscriber.h.
|
private |
Definition at line 128 of file subscriber.h.