Publish consumed data on a ROS topic. More...
#include <publisher.h>
Public Member Functions | |
void | advertise (ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, bool latch=false, ros::CallbackQueueInterface *callback_queue=nullptr) noexcept |
Advertise ROS topic. More... | |
void | advertise (ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::SubscriberStatusCallback &connect_cb, const ros::SubscriberStatusCallback &disconnect_cb=ros::SubscriberStatusCallback(), const ros::VoidConstPtr &tracked_object=ros::VoidConstPtr(), bool latch=false, ros::CallbackQueueInterface *callback_queue=nullptr) noexcept |
Advertise ROS topic with subscriber status callbacks. More... | |
virtual bool | is_active () const noexcept override |
Check if the ROS publisher has at least one subscriber. More... | |
Publisher () noexcept | |
Constructs an empty publisher. More... | |
Publisher (ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, bool latch=false, ros::CallbackQueueInterface *callback_queue=nullptr) noexcept | |
Constructor that advertises the given ROS topic. More... | |
virtual std::string | topic () const noexcept override |
Return the configured ROS topic. More... | |
Private Member Functions | |
virtual void | receive (const typename Translate< M >::FilterType &t) noexcept override |
Private Attributes | |
ros::Publisher | pub_ |
Additional Inherited Members |
Publish consumed data on a ROS topic.
This class together with the Subscriber class is the generic interface between ROS and this library. All messages which are received from the connected sources will be published on the advertised ROS topic. For maximum flexibility, you can choose one of four ways how to receive messages from your sources:
Publisher<M, RosMessageEvent>
will act as a sink of ros::MessageEvent<const M>
objects (default) Publisher<M, RosMessageConstPtr>
will act as a sink of M::ConstPtr
objects (as of this writing, this is a boost::shared_ptr<const M>
) Publisher<M, RosMessageStdSharedPtr>
will act as a sink of std::shared_ptr<const M>
objects Publisher<M, RosMessage>
will act as a sink of plain M
objectsUnlike regular ROS publishers, this class can be associated with one or more subscriber instances. In that case, the subscribers will subscribe to their ROS topics only if the publisher is actively used. This is a convenient method to save processing power if the filter pipeline is used only intermittently.
Definition at line 51 of file publisher.h.
|
noexcept |
Constructs an empty publisher.
You need to call advertise() to actually publish to a ROS topic.
Definition at line 30 of file publisher_impl.h.
|
noexcept |
Constructor that advertises the given ROS topic.
The constructor calls advertise() for you.
Definition at line 35 of file publisher_impl.h.
|
noexcept |
Advertise ROS topic.
All arguments are passed to the ROS client library; see the ROS documentation for further information. Calling this method will automatically unadvertise any previously advertised ROS topic.
nh
ROS node handle to create the ROS advertisement topic
name of the ROS topic, subject to remapping queue_size
size of the ROS publishing queue latch
if true, the last published message remains available for later subscribers callback_queue
custom ROS callback queueDefinition at line 53 of file publisher_impl.h.
|
noexcept |
Advertise ROS topic with subscriber status callbacks.
All arguments are passed to the ROS client library; see the ROS documentation for further information. Calling this method will automatically unadvertise any previously advertised ROS topic.
nh
ROS node handle to create the ROS advertisement topic
name of the ROS topic, subject to remapping queue_size
size of the ROS publishing queue connect_cb
callback that is invoked each time a new subscriber connects to the advertised topic disconnect_cb
callback that is invoked each time an existing subscriber disconnects from the advertised topic tracked_object
an associated object whose lifetime will limit the lifetime of the advertised topic latch
if true, the last published message remains available for later subscribers callback_queue
custom ROS callback queueDefinition at line 73 of file publisher_impl.h.
|
overridevirtualnoexcept |
Check if the ROS publisher has at least one subscriber.
Implements fkie_message_filters::PublisherBase.
Definition at line 41 of file publisher_impl.h.
|
overrideprivatevirtualnoexcept |
Definition at line 96 of file publisher_impl.h.
|
overridevirtualnoexcept |
Return the configured ROS topic.
Implements fkie_message_filters::PublisherBase.
Definition at line 47 of file publisher_impl.h.
|
private |
Definition at line 114 of file publisher.h.