Class Publisher
Defined in File publisher.hpp
Class Documentation
-
class Publisher
Manages advertisements of multiple transport options on an Image topic.
Publisher is a drop-in replacement for ros::Publisher when publishing Image topics. In a minimally built environment, they behave the same; however, Publisher is extensible via plugins to publish alternative representations of the image on related subtopics. This is especially useful for limiting bandwidth and latency over a network connection, when you might (for example) use the theora plugin to transport the images as streamed video. All topics are published only on demand (i.e. if there are subscribers).
A Publisher should always be created through a call to ImageTransport::advertise(), or copied from one that was. Once all copies of a specific Publisher go out of scope, any subscriber callbacks associated with that handle will stop being called. Once all Publisher for a given base topic go out of scope the topic (and all subtopics) will be unadvertised.
Public Functions
-
IMAGE_TRANSPORT_PUBLIC Publisher() = default
-
IMAGE_TRANSPORT_PUBLIC Publisher(rclcpp::Node *nh, const std::string &base_topic, PubLoaderPtr loader, rmw_qos_profile_t custom_qos, rclcpp::PublisherOptions options = rclcpp::PublisherOptions())
- IMAGE_TRANSPORT_PUBLIC size_t getNumSubscribers () const
Returns the number of subscribers that are currently connected to this Publisher.
Returns the total number of subscribers to all advertised topics.
- IMAGE_TRANSPORT_PUBLIC std::string getTopic () const
Returns the base topic of this Publisher.
- IMAGE_TRANSPORT_PUBLIC void publish (const sensor_msgs::msg::Image &message) const
Publish an image on the topics associated with this Publisher.
- IMAGE_TRANSPORT_PUBLIC void publish (const sensor_msgs::msg::Image::ConstSharedPtr &message) const
Publish an image on the topics associated with this Publisher.
- IMAGE_TRANSPORT_PUBLIC void shutdown ()
Shutdown the advertisements associated with this Publisher.
-
IMAGE_TRANSPORT_PUBLIC operator void*() const
- inline IMAGE_TRANSPORT_PUBLIC bool operator< (const Publisher &rhs) const
- inline IMAGE_TRANSPORT_PUBLIC bool operator!= (const Publisher &rhs) const
- inline IMAGE_TRANSPORT_PUBLIC bool operator== (const Publisher &rhs) const
-
IMAGE_TRANSPORT_PUBLIC Publisher() = default