Classes | Public Member Functions | Private Member Functions | Private Attributes | Friends | List of all members
camera_throttle::RgbdCameraPublisher Class Reference

Manages advertisements for publishing RGBD camera images. More...

#include <rgbd_camera_publisher.h>

Classes

struct  Impl
 

Public Member Functions

std::string getDepthInfoTopic () const
 Returns the depth camera info topic of this CameraPublisher. More...
 
std::string getDepthTopic () const
 Returns the depth base (image) topic of this CameraPublisher. More...
 
size_t getNumSubscribers () const
 Returns the number of subscribers that are currently connected to this CameraPublisher. More...
 
std::string getPclTopic () const
 Get the topic of the pointcloud (can be empty if pointcloud is not processed). More...
 
std::string getRGBInfoTopic () const
 Returns the RGB camera info topic of this CameraPublisher. More...
 
std::string getRGBTopic () const
 Returns the RGB base (image) topic of this CameraPublisher. More...
 
 operator void * () const
 
bool operator!= (const RgbdCameraPublisher &rhs) const
 
bool operator< (const RgbdCameraPublisher &rhs) const
 
bool operator== (const RgbdCameraPublisher &rhs) const
 
void publish (const sensor_msgs::Image &rgb_image, const sensor_msgs::CameraInfo &rgb_info, const sensor_msgs::Image &depth_image, const sensor_msgs::CameraInfo &depth_info) const
 Publish an RGB and depth (image, info) pair on the topics associated with this RgbdCameraPublisher. More...
 
void publish (const sensor_msgs::Image &rgb_image, const sensor_msgs::CameraInfo &rgb_info, const sensor_msgs::Image &depth_image, const sensor_msgs::CameraInfo &depth_info, const sensor_msgs::PointCloud2 &pcl) const
 Publish an RGB and depth (image, info) pair and PCL on the topics associated with this RgbdCameraPublisher. More...
 
void publish (const sensor_msgs::ImageConstPtr &rgb_image, const sensor_msgs::CameraInfoConstPtr &rgb_info, const sensor_msgs::ImageConstPtr &depth_image, const sensor_msgs::CameraInfoConstPtr &depth_info) const
 Publish an RGB and depth (image, info) pair on the topics associated with this RgbdCameraPublisher. More...
 
void publish (const sensor_msgs::ImageConstPtr &rgb_image, const sensor_msgs::CameraInfoConstPtr &rgb_info, const sensor_msgs::ImageConstPtr &depth_image, const sensor_msgs::CameraInfoConstPtr &depth_info, const sensor_msgs::PointCloud2ConstPtr &pcl) const
 Publish an RGB and depth (image, info) pair and PCL on the topics associated with this RgbdCameraPublisher. More...
 
void publish (sensor_msgs::Image &rgb_image, sensor_msgs::CameraInfo &rgb_info, sensor_msgs::Image &depth_image, sensor_msgs::CameraInfo &depth_info, ros::Time stamp) const
 Publish an RGB and depth (image, info) pair with given timestamp on the topics associated with this RgbdCameraPublisher. More...
 
void publish (sensor_msgs::Image &rgb_image, sensor_msgs::CameraInfo &rgb_info, sensor_msgs::Image &depth_image, sensor_msgs::CameraInfo &depth_info, sensor_msgs::PointCloud2 &pcl, ros::Time stamp) const
 Publish an RGB and depth (image, info) pair and PCL with given timestamp on the topics associated with this RgbdCameraPublisher. More...
 
 RgbdCameraPublisher ()=default
 
void shutdown ()
 Shutdown the advertisements associated with this Publisher. More...
 
virtual ~RgbdCameraPublisher ()=default
 

Private Member Functions

 RgbdCameraPublisher (RgbdImageTransport &image_it, ros::NodeHandle &rgb_nh, ros::NodeHandle &depth_nh, const std::string &rgb_base_topic, const std::string &depth_base_topic, size_t queue_size, const image_transport::SubscriberStatusCallback &rgb_connect_cb, const image_transport::SubscriberStatusCallback &rgb_disconnect_cb, const image_transport::SubscriberStatusCallback &depth_connect_cb, const image_transport::SubscriberStatusCallback &depth_disconnect_cb, const ros::SubscriberStatusCallback &rgb_info_connect_cb, const ros::SubscriberStatusCallback &rgb_info_disconnect_cb, const ros::SubscriberStatusCallback &depth_info_connect_cb, const ros::SubscriberStatusCallback &depth_info_disconnect_cb, const ros::VoidPtr &tracked_object, bool latch)
 
 RgbdCameraPublisher (RgbdImageTransport &image_it, ros::NodeHandle &rgb_nh, ros::NodeHandle &depth_nh, ros::NodeHandle &pcl_nh, const std::string &rgb_base_topic, const std::string &depth_base_topic, const std::string &pcl_topic, size_t queue_size, const image_transport::SubscriberStatusCallback &rgb_connect_cb, const image_transport::SubscriberStatusCallback &rgb_disconnect_cb, const image_transport::SubscriberStatusCallback &depth_connect_cb, const image_transport::SubscriberStatusCallback &depth_disconnect_cb, const ros::SubscriberStatusCallback &pcl_connect_cb, const ros::SubscriberStatusCallback &pcl_disconnect_cb, const ros::SubscriberStatusCallback &rgb_info_connect_cb, const ros::SubscriberStatusCallback &rgb_info_disconnect_cb, const ros::SubscriberStatusCallback &depth_info_connect_cb, const ros::SubscriberStatusCallback &depth_info_disconnect_cb, const ros::VoidPtr &tracked_object, bool latch)
 

Private Attributes

std::shared_ptr< Implimpl
 

Friends

class RgbdImageTransport
 

Detailed Description

Manages advertisements for publishing RGBD camera images.

RgbdCameraPublisher is a convenience class for publishing synchronized image, camera info and pointcloud topics using the standard topic naming convention, where the info topic name is "camera_info" in the same namespace as the base image topic.

On the client side, RgbdCameraSubscriber simplifies subscribing to camera images.

A RgbdCameraPublisher should always be created through a call to RgbdImageTransport::advertiseCamera(), or copied from one that was. Once all copies of a specific RgbdCameraPublisher go out of scope, any subscriber callbacks associated with that handle will stop being called. Once all RgbdCameraPublisher for a given base topic go out of scope the topic (and all subtopics) will be unadvertised.

Definition at line 30 of file rgbd_camera_publisher.h.

Constructor & Destructor Documentation

◆ RgbdCameraPublisher() [1/3]

camera_throttle::RgbdCameraPublisher::RgbdCameraPublisher ( )
default

◆ ~RgbdCameraPublisher()

virtual camera_throttle::RgbdCameraPublisher::~RgbdCameraPublisher ( )
virtualdefault

◆ RgbdCameraPublisher() [2/3]

camera_throttle::RgbdCameraPublisher::RgbdCameraPublisher ( RgbdImageTransport image_it,
ros::NodeHandle rgb_nh,
ros::NodeHandle depth_nh,
const std::string &  rgb_base_topic,
const std::string &  depth_base_topic,
size_t  queue_size,
const image_transport::SubscriberStatusCallback rgb_connect_cb,
const image_transport::SubscriberStatusCallback rgb_disconnect_cb,
const image_transport::SubscriberStatusCallback depth_connect_cb,
const image_transport::SubscriberStatusCallback depth_disconnect_cb,
const ros::SubscriberStatusCallback rgb_info_connect_cb,
const ros::SubscriberStatusCallback rgb_info_disconnect_cb,
const ros::SubscriberStatusCallback depth_info_connect_cb,
const ros::SubscriberStatusCallback depth_info_disconnect_cb,
const ros::VoidPtr tracked_object,
bool  latch 
)
private

Definition at line 46 of file rgbd_camera_publisher.cpp.

◆ RgbdCameraPublisher() [3/3]

camera_throttle::RgbdCameraPublisher::RgbdCameraPublisher ( RgbdImageTransport image_it,
ros::NodeHandle rgb_nh,
ros::NodeHandle depth_nh,
ros::NodeHandle pcl_nh,
const std::string &  rgb_base_topic,
const std::string &  depth_base_topic,
const std::string &  pcl_topic,
size_t  queue_size,
const image_transport::SubscriberStatusCallback rgb_connect_cb,
const image_transport::SubscriberStatusCallback rgb_disconnect_cb,
const image_transport::SubscriberStatusCallback depth_connect_cb,
const image_transport::SubscriberStatusCallback depth_disconnect_cb,
const ros::SubscriberStatusCallback pcl_connect_cb,
const ros::SubscriberStatusCallback pcl_disconnect_cb,
const ros::SubscriberStatusCallback rgb_info_connect_cb,
const ros::SubscriberStatusCallback rgb_info_disconnect_cb,
const ros::SubscriberStatusCallback depth_info_connect_cb,
const ros::SubscriberStatusCallback depth_info_disconnect_cb,
const ros::VoidPtr tracked_object,
bool  latch 
)
private

Definition at line 78 of file rgbd_camera_publisher.cpp.

Member Function Documentation

◆ getDepthInfoTopic()

std::string camera_throttle::RgbdCameraPublisher::getDepthInfoTopic ( ) const

Returns the depth camera info topic of this CameraPublisher.

Definition at line 143 of file rgbd_camera_publisher.cpp.

◆ getDepthTopic()

std::string camera_throttle::RgbdCameraPublisher::getDepthTopic ( ) const

Returns the depth base (image) topic of this CameraPublisher.

Definition at line 137 of file rgbd_camera_publisher.cpp.

◆ getNumSubscribers()

size_t camera_throttle::RgbdCameraPublisher::getNumSubscribers ( ) const

Returns the number of subscribers that are currently connected to this CameraPublisher.

Returns max(image topic subscribers, info topic subscribers).

Definition at line 115 of file rgbd_camera_publisher.cpp.

◆ getPclTopic()

std::string camera_throttle::RgbdCameraPublisher::getPclTopic ( ) const

Get the topic of the pointcloud (can be empty if pointcloud is not processed).

Definition at line 149 of file rgbd_camera_publisher.cpp.

◆ getRGBInfoTopic()

std::string camera_throttle::RgbdCameraPublisher::getRGBInfoTopic ( ) const

Returns the RGB camera info topic of this CameraPublisher.

Definition at line 131 of file rgbd_camera_publisher.cpp.

◆ getRGBTopic()

std::string camera_throttle::RgbdCameraPublisher::getRGBTopic ( ) const

Returns the RGB base (image) topic of this CameraPublisher.

Definition at line 125 of file rgbd_camera_publisher.cpp.

◆ operator void *()

camera_throttle::RgbdCameraPublisher::operator void * ( ) const
explicit

Definition at line 263 of file rgbd_camera_publisher.cpp.

◆ operator!=()

bool camera_throttle::RgbdCameraPublisher::operator!= ( const RgbdCameraPublisher rhs) const
inline

Definition at line 123 of file rgbd_camera_publisher.h.

◆ operator<()

bool camera_throttle::RgbdCameraPublisher::operator< ( const RgbdCameraPublisher rhs) const
inline

Definition at line 122 of file rgbd_camera_publisher.h.

◆ operator==()

bool camera_throttle::RgbdCameraPublisher::operator== ( const RgbdCameraPublisher rhs) const
inline

Definition at line 124 of file rgbd_camera_publisher.h.

◆ publish() [1/6]

void camera_throttle::RgbdCameraPublisher::publish ( const sensor_msgs::Image &  rgb_image,
const sensor_msgs::CameraInfo &  rgb_info,
const sensor_msgs::Image &  depth_image,
const sensor_msgs::CameraInfo &  depth_info 
) const

Publish an RGB and depth (image, info) pair on the topics associated with this RgbdCameraPublisher.

Definition at line 155 of file rgbd_camera_publisher.cpp.

◆ publish() [2/6]

void camera_throttle::RgbdCameraPublisher::publish ( const sensor_msgs::Image &  rgb_image,
const sensor_msgs::CameraInfo &  rgb_info,
const sensor_msgs::Image &  depth_image,
const sensor_msgs::CameraInfo &  depth_info,
const sensor_msgs::PointCloud2 &  pcl 
) const

Publish an RGB and depth (image, info) pair and PCL on the topics associated with this RgbdCameraPublisher.

Definition at line 170 of file rgbd_camera_publisher.cpp.

◆ publish() [3/6]

void camera_throttle::RgbdCameraPublisher::publish ( const sensor_msgs::ImageConstPtr &  rgb_image,
const sensor_msgs::CameraInfoConstPtr &  rgb_info,
const sensor_msgs::ImageConstPtr &  depth_image,
const sensor_msgs::CameraInfoConstPtr &  depth_info 
) const

Publish an RGB and depth (image, info) pair on the topics associated with this RgbdCameraPublisher.

Definition at line 188 of file rgbd_camera_publisher.cpp.

◆ publish() [4/6]

void camera_throttle::RgbdCameraPublisher::publish ( const sensor_msgs::ImageConstPtr &  rgb_image,
const sensor_msgs::CameraInfoConstPtr &  rgb_info,
const sensor_msgs::ImageConstPtr &  depth_image,
const sensor_msgs::CameraInfoConstPtr &  depth_info,
const sensor_msgs::PointCloud2ConstPtr &  pcl 
) const

Publish an RGB and depth (image, info) pair and PCL on the topics associated with this RgbdCameraPublisher.

Definition at line 203 of file rgbd_camera_publisher.cpp.

◆ publish() [5/6]

void camera_throttle::RgbdCameraPublisher::publish ( sensor_msgs::Image &  rgb_image,
sensor_msgs::CameraInfo &  rgb_info,
sensor_msgs::Image &  depth_image,
sensor_msgs::CameraInfo &  depth_info,
ros::Time  stamp 
) const

Publish an RGB and depth (image, info) pair with given timestamp on the topics associated with this RgbdCameraPublisher.

Convenience version, which sets the timestamps of both image and info to stamp before publishing.

Definition at line 221 of file rgbd_camera_publisher.cpp.

◆ publish() [6/6]

void camera_throttle::RgbdCameraPublisher::publish ( sensor_msgs::Image &  rgb_image,
sensor_msgs::CameraInfo &  rgb_info,
sensor_msgs::Image &  depth_image,
sensor_msgs::CameraInfo &  depth_info,
sensor_msgs::PointCloud2 &  pcl,
ros::Time  stamp 
) const

Publish an RGB and depth (image, info) pair and PCL with given timestamp on the topics associated with this RgbdCameraPublisher.

Convenience version, which sets the timestamps of both image and info to stamp before publishing.

Definition at line 237 of file rgbd_camera_publisher.cpp.

◆ shutdown()

void camera_throttle::RgbdCameraPublisher::shutdown ( )

Shutdown the advertisements associated with this Publisher.

Definition at line 255 of file rgbd_camera_publisher.cpp.

Friends And Related Function Documentation

◆ RgbdImageTransport

friend class RgbdImageTransport
friend

Definition at line 157 of file rgbd_camera_publisher.h.

Member Data Documentation

◆ impl

std::shared_ptr<Impl> camera_throttle::RgbdCameraPublisher::impl
private

Definition at line 154 of file rgbd_camera_publisher.h.


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


camera_throttle
Author(s): Martin Pecka
autogenerated on Sat Dec 14 2024 03:51:15