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

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

Definition at line 72 of file camera_subscriber.h.

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

Definition at line 74 of file camera_subscriber.h.


Constructor & Destructor Documentation

image_transport::CameraSubscriber::CameraSubscriber (  )  [inline]

Definition at line 33 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 65 of file camera_subscriber.cpp.


Member Function Documentation

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

Get the camera info topic.

Definition at line 95 of file camera_subscriber.cpp.

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 101 of file camera_subscriber.cpp.

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

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

Definition at line 89 of file camera_subscriber.cpp.

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

Returns the name of the transport being used.

Definition at line 109 of file camera_subscriber.cpp.

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

Definition at line 120 of file camera_subscriber.cpp.

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

Definition at line 62 of file camera_subscriber.h.

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

Definition at line 61 of file camera_subscriber.h.

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

Definition at line 63 of file camera_subscriber.h.

void image_transport::CameraSubscriber::shutdown (  ) 

Unsubscribe the callback associated with this CameraSubscriber.

Definition at line 115 of file camera_subscriber.cpp.


Friends And Related Function Documentation

friend class ImageTransport [friend]

Definition at line 78 of file camera_subscriber.h.


Member Data Documentation

Definition at line 76 of file camera_subscriber.h.


The documentation for this class was generated from the following files:
 All Classes Namespaces Files Functions Variables Typedefs Enumerations Enumerator Friends


image_transport
Author(s): Patrick Mihelich
autogenerated on Fri Jan 11 09:40:41 2013