Classes | Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes | Friends | List of all members
image_transport::CameraSubscriber Class Reference

Manages a subscription callback on synchronized Image and CameraInfo topics. More...

#include <camera_subscriber.h>

Classes

struct  Impl
 

Public Types

typedef boost::function< void(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &)> Callback
 

Public Member Functions

 CameraSubscriber ()
 
std::string getInfoTopic () const
 Get the camera info topic. More...
 
uint32_t getNumPublishers () const
 Returns the number of publishers this subscriber is connected to. More...
 
std::string getTopic () const
 Get the base topic (on which the raw image is published). More...
 
std::string getTransport () const
 Returns the name of the transport being used. More...
 
 operator void * () const
 
bool operator!= (const CameraSubscriber &rhs) const
 
bool operator< (const CameraSubscriber &rhs) const
 
bool operator== (const CameraSubscriber &rhs) const
 
void shutdown ()
 Unsubscribe the callback associated with this CameraSubscriber. More...
 

Private Types

typedef boost::shared_ptr< ImplImplPtr
 
typedef boost::weak_ptr< ImplImplWPtr
 

Private Member Functions

 CameraSubscriber (ImageTransport &image_it, ros::NodeHandle &info_nh, const std::string &base_topic, uint32_t queue_size, const Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
 

Private Attributes

ImplPtr impl_
 

Friends

class ImageTransport
 

Detailed Description

Manages a subscription callback on synchronized Image and CameraInfo topics.

CameraSubscriber is the client-side counterpart to CameraPublisher, and assumes the same topic naming convention. The callback is of type:

void callback(const sensor_msgs::ImageConstPtr&, const sensor_msgs::CameraInfoConstPtr&);

A CameraSubscriber should always be created through a call to ImageTransport::subscribeCamera(), or copied from one that was. Once all copies of a specific CameraSubscriber go out of scope, the subscription callback associated with that handle will stop being called. Once all CameraSubscriber for a given topic go out of scope the topic will be unsubscribed.

Definition at line 95 of file camera_subscriber.h.

Member Typedef Documentation

◆ Callback

typedef boost::function<void(const sensor_msgs::ImageConstPtr&, const sensor_msgs::CameraInfoConstPtr&)> image_transport::CameraSubscriber::Callback

Definition at line 99 of file camera_subscriber.h.

◆ ImplPtr

Definition at line 140 of file camera_subscriber.h.

◆ ImplWPtr

typedef boost::weak_ptr<Impl> image_transport::CameraSubscriber::ImplWPtr
private

Definition at line 142 of file camera_subscriber.h.

Constructor & Destructor Documentation

◆ CameraSubscriber() [1/2]

image_transport::CameraSubscriber::CameraSubscriber ( )
inline

Definition at line 101 of file camera_subscriber.h.

◆ CameraSubscriber() [2/2]

image_transport::CameraSubscriber::CameraSubscriber ( ImageTransport image_it,
ros::NodeHandle info_nh,
const std::string &  base_topic,
uint32_t  queue_size,
const Callback callback,
const ros::VoidPtr tracked_object = ros::VoidPtr(),
const TransportHints transport_hints = TransportHints() 
)
private

Definition at line 100 of file camera_subscriber.cpp.

Member Function Documentation

◆ getInfoTopic()

std::string image_transport::CameraSubscriber::getInfoTopic ( ) const

Get the camera info topic.

Definition at line 130 of file camera_subscriber.cpp.

◆ getNumPublishers()

uint32_t image_transport::CameraSubscriber::getNumPublishers ( ) const

Returns the number of publishers this subscriber is connected to.

Todo:
Fix this when message_filters::Subscriber has getNumPublishers()

Definition at line 136 of file camera_subscriber.cpp.

◆ getTopic()

std::string image_transport::CameraSubscriber::getTopic ( ) const

Get the base topic (on which the raw image is published).

Definition at line 124 of file camera_subscriber.cpp.

◆ getTransport()

std::string image_transport::CameraSubscriber::getTransport ( ) const

Returns the name of the transport being used.

Definition at line 144 of file camera_subscriber.cpp.

◆ operator void *()

image_transport::CameraSubscriber::operator void * ( ) const

Definition at line 155 of file camera_subscriber.cpp.

◆ operator!=()

bool image_transport::CameraSubscriber::operator!= ( const CameraSubscriber rhs) const
inline

Definition at line 130 of file camera_subscriber.h.

◆ operator<()

bool image_transport::CameraSubscriber::operator< ( const CameraSubscriber rhs) const
inline

Definition at line 129 of file camera_subscriber.h.

◆ operator==()

bool image_transport::CameraSubscriber::operator== ( const CameraSubscriber rhs) const
inline

Definition at line 131 of file camera_subscriber.h.

◆ shutdown()

void image_transport::CameraSubscriber::shutdown ( )

Unsubscribe the callback associated with this CameraSubscriber.

Definition at line 150 of file camera_subscriber.cpp.

Friends And Related Function Documentation

◆ ImageTransport

friend class ImageTransport
friend

Definition at line 146 of file camera_subscriber.h.

Member Data Documentation

◆ impl_

ImplPtr image_transport::CameraSubscriber::impl_
private

Definition at line 144 of file camera_subscriber.h.


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


image_transport
Author(s): Patrick Mihelich
autogenerated on Sat Jan 20 2024 03:14:50