Publish consumed data to ROS camera topics. More...
#include <camera_publisher.h>
Public Member Functions | |
void | advertise (const image_transport::ImageTransport &it, const std::string &base_topic, uint32_t queue_size, bool latch=false) noexcept |
Advertise ROS camera topic. More... | |
void | advertise (const image_transport::ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const image_transport::SubscriberStatusCallback &image_connect_cb, const image_transport::SubscriberStatusCallback &image_disconnect_cb=image_transport::SubscriberStatusCallback(), const ros::SubscriberStatusCallback &info_connect_cb=ros::SubscriberStatusCallback(), const ros::SubscriberStatusCallback &info_disconnect_cb=ros::SubscriberStatusCallback(), const ros::VoidPtr &tracked_object=ros::VoidPtr(), bool latch=false) noexcept |
Advertise ROS camera topic with subscriber status callbacks. More... | |
CameraPublisher () noexcept | |
Constructs an empty publisher. More... | |
CameraPublisher (const image_transport::ImageTransport &it, const std::string &base_topic, uint32_t queue_size, bool latch=false) noexcept | |
Constructor that advertises the given ROS camera topic. More... | |
virtual bool | is_active () const noexcept override |
Check if the ROS publisher has at least one subscriber. More... | |
virtual std::string | topic () const noexcept override |
Return the configured ROS topic. More... | |
Private Member Functions | |
void | receive (const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &) noexcept override |
Private Attributes | |
std::shared_ptr< image_transport::ImageTransport > | it_ |
image_transport::CameraPublisher | pub_ |
Additional Inherited Members |
Publish consumed data to ROS camera topics.
This is a specialized publisher that uses image_transport to publish ROS camera topics. All messages which are received from the connected sources will be published on the corresponding advertised ROS topics.
Unlike 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 62 of file camera_publisher.h.
|
inlinenoexcept |
Constructs an empty publisher.
You need to call advertise() to actually publish to a ROS topic.
\nothrow
Definition at line 89 of file camera_publisher.h.
|
noexcept |
Constructor that advertises the given ROS camera topic.
The constructor calls advertise() for you.
\nothrow
Definition at line 44 of file camera_publisher.cpp.
|
noexcept |
Advertise ROS camera 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.
it
ROS image_transport instance to handle the publishing base_topic
name of the ROS image topic, subject to remapping queue_size
size of the ROS publishing queue latch
if true, the last published message remains available for later subscribers\nothrow
Definition at line 59 of file camera_publisher.cpp.
|
noexcept |
Advertise ROS camera 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.
it
ROS image_transport instance to handle the publishing base_topic
name of the ROS image topic, subject to remapping queue_size
size of the ROS publishing queue image_connect_cb
callback that is invoked each time a new subscriber connects to the advertised image topic image_disconnect_cb
callback that is invoked each time an existing subscriber disconnects from the advertised image topic info_connect_cb
callback that is invoked each time a new subscriber connects to the advertised camera info topic info_disconnect_cb
callback that is invoked each time an existing subscriber disconnects from the advertised camera info topic tracked_object
an associated object whose lifetime will limit the lifetimes of the advertised topics latch
if true, the last published message remains available for later subscribers\nothrow
Definition at line 86 of file camera_publisher.cpp.
|
overridevirtualnoexcept |
Check if the ROS publisher has at least one subscriber.
\nothrow
Implements fkie_message_filters::PublisherBase.
Definition at line 49 of file camera_publisher.cpp.
|
overrideprivatenoexcept |
Definition at line 117 of file camera_publisher.cpp.
|
overridevirtualnoexcept |
Return the configured ROS topic.
\nothrow
Implements fkie_message_filters::PublisherBase.
Definition at line 54 of file camera_publisher.cpp.
|
private |
Definition at line 142 of file camera_publisher.h.
|
private |
Definition at line 143 of file camera_publisher.h.