FKIE Message Filters
Improved filters for processing ROS messages
|
Publish consumed data on a ROS topic. More...
#include <fkie_message_filters/publisher.hpp>
Public Types | |
using | Input = IO< Inputs... > |
Grouped input types. | |
Public Member Functions | |
Publisher () noexcept | |
Constructs an empty publisher. | |
Publisher (rclcpp::Node::SharedPtr &node, const std::string &topic, const rclcpp::QoS &qos=rclcpp::QoS(rclcpp::KeepLast(10), rmw_qos_profile_default), const rclcpp::PublisherOptions &options=rclcpp::PublisherOptions()) noexcept | |
Constructor that advertises the given ROS topic. | |
virtual | ~Publisher () |
Destructor. | |
void | advertise (rclcpp::Node::SharedPtr &node, const std::string &topic, const rclcpp::QoS &qos=rclcpp::QoS(rclcpp::KeepLast(10), rmw_qos_profile_default), const rclcpp::PublisherOptions &options=rclcpp::PublisherOptions()) noexcept |
Advertise ROS topic. | |
Connection | connect_to_source (Source< Inputs... > &src) noexcept |
Connect this sink to a source. | |
virtual void | disconnect () noexcept override |
Disconnect from all connected sources. | |
void | disconnect_from_all_sources () noexcept |
Disconnect from all connected sources. | |
virtual bool | is_active () const noexcept override |
Check if the ROS publisher has at least one subscriber. | |
virtual void | reset () noexcept |
Reset filter state. | |
virtual std::string | topic () const noexcept override |
Return the configured ROS topic. | |
Static Public Attributes | |
static constexpr std::size_t | NUM_INPUTS = sizeof...(Inputs) |
Number of input arguments. | |
Protected Member Functions | |
std::tuple< Connection, Connection > | link_with_subscriber (SubscriberBase &sub) |
Add a new subscriber that will be controlled by this publisher. | |
virtual void | receive (helpers::argument_t< Inputs >... in)=0 |
Process incoming data. | |
void | shutdown_monitor () noexcept |
Shutdown monitoring thread for the number of subscribers. | |
void | start_monitor (const rclcpp::Node::SharedPtr &node) noexcept |
Start monitoring thread for the number of subscribers. | |
void | update_subscriber_state () |
Cause all linked subscribers to subscribe or unsubscribe to their ROS topics. | |
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 how to receive messages from your sources:
Publisher<M, RosMessageSharedPtr>
will act as a sink of M::ConstSharedPtr
objects (default) Publisher<M, RosMessageUniquePtr>
will act as a sink of M::UniquePtr
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.
|
inherited |
Grouped input types.
This type can be used to define sources with matching types.
|
noexcept |
Constructs an empty publisher.
You need to call advertise() to actually publish to a ROS topic.
|
noexcept |
Constructor that advertises the given ROS topic.
The constructor calls advertise() for you.
|
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.
node
ROS node instance to create the ROS publisher topic
name of the ROS topic, subject to remapping qos
the ROS quality of service specification options
ROS publisher options
|
noexceptinherited |
Connect this sink to a source.
Can be called multiple times to connect multiple sources; in that case, the sink receives data from all connected sources. This function does basically the same thing as Source::connect_to_sink(), only from the opposite point of view.
src
the source that is to be connected
|
overridevirtualnoexceptinherited |
Disconnect from all connected sources.
The sink implementation calls disconnect_from_all_sources().
Implements fkie_message_filters::FilterBase.
Reimplemented in fkie_message_filters::Divider< Inputs >, fkie_message_filters::Filter< In, Out >, fkie_message_filters::Filter< IO< Inputs... >, IO< Inputs... > >, fkie_message_filters::Filter< IO< Inputs... >, IO< Inputs... >::template Select< Is... > >, and fkie_message_filters::Filter< IO< Inputs... >, IO< Outputs... > >.
|
noexceptinherited |
Disconnect from all connected sources.
Severs the connection to all sources. The receive() method will not be called any more.
|
overridevirtualnoexcept |
Check if the ROS publisher has at least one subscriber.
node
ROS node instance to create the ROS publisher topic
name of the ROS topic, subject to remapping qos
the ROS quality of service specification options
ROS publisher optionsImplements fkie_message_filters::PublisherBase.
|
protectedinherited |
Add a new subscriber that will be controlled by this publisher.
sub
the subscriber
|
protectedpure virtualinherited |
Process incoming data.
Derived classes need to override this method to handle all data that is to be consumed by the sink.
Implemented in fkie_message_filters::Buffer< Inputs >, fkie_message_filters::Divider< Inputs >, fkie_message_filters::Selector< Inputs, Is >, fkie_message_filters::Sequencer< Inputs >, fkie_message_filters::SimpleUserFilter< Inputs >, fkie_message_filters::TfFilter< Inputs >, fkie_message_filters::TfFilter< Inputs... >, and fkie_message_filters::UserFilter< Inputs, Outputs >.
Reset filter state.
For stateful filters, this method resets the internal state as if the filter had just been created. Existing connections to sources and sinks are unaffected.
The default implementation does nothing.
Reimplemented in fkie_message_filters::Buffer< Inputs >, fkie_message_filters::Combiner< PolicyTmpl, IOs >, fkie_message_filters::Sequencer< Inputs >, fkie_message_filters::TfFilter< Inputs >, and fkie_message_filters::TfFilter< Inputs... >.
|
protectednoexceptinherited |
Shutdown monitoring thread for the number of subscribers.
This function is called automatically when the publisher object is destroyed.
|
protectednoexceptinherited |
Start monitoring thread for the number of subscribers.
This is needed in ROS 2 because there is no longer a dedicated callback for created publishers.
|
overridevirtualnoexcept |
Return the configured ROS topic.
Implements fkie_message_filters::PublisherBase.
|
protectedinherited |
Cause all linked subscribers to subscribe or unsubscribe to their ROS topics.
This will check the return value of is_active() to determine if the publisher is active, and then call SubscriberBase::subscribe_impl() or SubscriberBase::unsubscribe_impl() accordingly.