Public Member Functions | Private Member Functions | Private Attributes | List of all members
fkie_message_filters::CameraPublisher Class Reference

Publish consumed data to ROS camera topics. More...

#include <camera_publisher.h>

Inheritance diagram for fkie_message_filters::CameraPublisher:
Inheritance graph
[legend]

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...
 
- Public Member Functions inherited from fkie_message_filters::PublisherBase
virtual ~PublisherBase ()
 
- Public Member Functions inherited from fkie_message_filters::Sink< sensor_msgs::ImageConstPtr, sensor_msgs::CameraInfoConstPtr >
Connection connect_to_source (Source< Inputs... > &src) noexcept
 Connect this sink to a source. More...
 
virtual void disconnect () noexcept override
 Disconnect from all connected sources. More...
 
void disconnect_from_all_sources () noexcept
 Disconnect from all connected sources. More...
 
virtual ~Sink ()
 
- Public Member Functions inherited from fkie_message_filters::FilterBase
virtual void reset () noexcept
 Reset filter state. More...
 
virtual ~FilterBase ()
 

Private Member Functions

void receive (const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &) noexcept override
 

Private Attributes

std::shared_ptr< image_transport::ImageTransportit_
 
image_transport::CameraPublisher pub_
 

Additional Inherited Members

- Public Types inherited from fkie_message_filters::Sink< sensor_msgs::ImageConstPtr, sensor_msgs::CameraInfoConstPtr >
using Input = IO< Inputs... >
 Grouped input types. More...
 
- Static Public Attributes inherited from fkie_message_filters::Sink< sensor_msgs::ImageConstPtr, sensor_msgs::CameraInfoConstPtr >
static constexpr std::size_t NUM_INPUTS
 Number of input arguments. More...
 
- Protected Member Functions inherited from fkie_message_filters::PublisherBase
std::tuple< boost::signals2::connection, boost::signals2::connection > link_with_subscriber (SubscriberBase &sub)
 Add a new subscriber that will be controlled by this publisher. More...
 
void update_subscriber_state ()
 Cause all linked subscribers to subscribe or unsubscribe to their ROS topics. More...
 
- Protected Member Functions inherited from fkie_message_filters::Sink< sensor_msgs::ImageConstPtr, sensor_msgs::CameraInfoConstPtr >
virtual void receive (const Inputs &... in)=0
 Process incoming data. More...
 

Detailed Description

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.

See also
CameraSubscriber, ImagePublisher, Publisher

Definition at line 44 of file camera_publisher.h.

Constructor & Destructor Documentation

◆ CameraPublisher() [1/2]

fkie_message_filters::CameraPublisher::CameraPublisher ( )
inlinenoexcept

Constructs an empty publisher.

You need to call advertise() to actually publish to a ROS topic.

Definition at line 53 of file camera_publisher.h.

◆ CameraPublisher() [2/2]

fkie_message_filters::CameraPublisher::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.

The constructor calls advertise() for you.

Definition at line 26 of file camera_publisher.cpp.

Member Function Documentation

◆ advertise() [1/2]

void fkie_message_filters::CameraPublisher::advertise ( const image_transport::ImageTransport it,
const std::string &  base_topic,
uint32_t  queue_size,
bool  latch = false 
)
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

Definition at line 41 of file camera_publisher.cpp.

◆ advertise() [2/2]

void fkie_message_filters::CameraPublisher::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.

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

Definition at line 68 of file camera_publisher.cpp.

◆ is_active()

bool fkie_message_filters::CameraPublisher::is_active ( ) const
overridevirtualnoexcept

Check if the ROS publisher has at least one subscriber.

Implements fkie_message_filters::PublisherBase.

Definition at line 31 of file camera_publisher.cpp.

◆ receive()

void fkie_message_filters::CameraPublisher::receive ( const sensor_msgs::ImageConstPtr &  img,
const sensor_msgs::CameraInfoConstPtr &  info 
)
overrideprivatenoexcept

Definition at line 99 of file camera_publisher.cpp.

◆ topic()

std::string fkie_message_filters::CameraPublisher::topic ( ) const
overridevirtualnoexcept

Return the configured ROS topic.

Implements fkie_message_filters::PublisherBase.

Definition at line 36 of file camera_publisher.cpp.

Member Data Documentation

◆ it_

std::shared_ptr<image_transport::ImageTransport> fkie_message_filters::CameraPublisher::it_
private

Definition at line 106 of file camera_publisher.h.

◆ pub_

image_transport::CameraPublisher fkie_message_filters::CameraPublisher::pub_
private

Definition at line 107 of file camera_publisher.h.


The documentation for this class was generated from the following files:


fkie_message_filters
Author(s): Timo Röhling
autogenerated on Mon Feb 28 2022 22:21:44