Classes | Public Types | Public Member Functions | Private Types | Private Member Functions | Private Attributes | Friends
image_transport::CameraSubscriber Class Reference

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

#include <camera_subscriber.h>

List of all members.

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.
uint32_t getNumPublishers () const
 Returns the number of publishers this subscriber is connected to.
std::string getTopic () const
 Get the base topic (on which the raw image is published).
std::string getTransport () const
 Returns the name of the transport being used.
 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.

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 62 of file camera_subscriber.h.


Member Typedef Documentation

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

Definition at line 66 of file camera_subscriber.h.

typedef boost::shared_ptr<Impl> image_transport::CameraSubscriber::ImplPtr [private]

Definition at line 107 of file camera_subscriber.h.

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

Definition at line 109 of file camera_subscriber.h.


Constructor & Destructor Documentation

Definition at line 68 of file camera_subscriber.h.

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

Get the camera info topic.

Definition at line 130 of file camera_subscriber.cpp.

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.

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

Definition at line 124 of file camera_subscriber.cpp.

Returns the name of the transport being used.

Definition at line 144 of file camera_subscriber.cpp.

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

Definition at line 155 of file camera_subscriber.cpp.

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

Definition at line 97 of file camera_subscriber.h.

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

Definition at line 96 of file camera_subscriber.h.

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

Definition at line 98 of file camera_subscriber.h.

Unsubscribe the callback associated with this CameraSubscriber.

Definition at line 150 of file camera_subscriber.cpp.


Friends And Related Function Documentation

friend class ImageTransport [friend]

Definition at line 113 of file camera_subscriber.h.


Member Data Documentation

Definition at line 111 of file camera_subscriber.h.


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


image_transport
Author(s): Patrick Mihelich
autogenerated on Tue Jun 6 2017 02:33:36