Manages advertisements for publishing camera images. More...
#include <camera_publisher.h>
Classes | |
struct | Impl |
Public Member Functions | |
CameraPublisher () | |
std::string | getInfoTopic () const |
Returns the camera info topic of this CameraPublisher. | |
uint32_t | getNumSubscribers () const |
Returns the number of subscribers that are currently connected to this CameraPublisher. | |
std::string | getTopic () const |
Returns the base (image) topic of this CameraPublisher. | |
operator void * () const | |
bool | operator!= (const CameraPublisher &rhs) const |
bool | operator< (const CameraPublisher &rhs) const |
bool | operator== (const CameraPublisher &rhs) const |
void | publish (const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const |
Publish an (image, info) pair on the topics associated with this CameraPublisher. | |
void | publish (const sensor_msgs::ImageConstPtr &image, const sensor_msgs::CameraInfoConstPtr &info) const |
Publish an (image, info) pair on the topics associated with this CameraPublisher. | |
void | publish (sensor_msgs::Image &image, sensor_msgs::CameraInfo &info, ros::Time stamp) const |
Publish an (image, info) pair with given timestamp on the topics associated with this CameraPublisher. | |
void | shutdown () |
Shutdown the advertisements associated with this Publisher. | |
Private Types | |
typedef boost::shared_ptr< Impl > | ImplPtr |
typedef boost::weak_ptr< Impl > | ImplWPtr |
Private Member Functions | |
CameraPublisher (ImageTransport &image_it, ros::NodeHandle &info_nh, const std::string &base_topic, uint32_t queue_size, const SubscriberStatusCallback &image_connect_cb, const SubscriberStatusCallback &image_disconnect_cb, const ros::SubscriberStatusCallback &info_connect_cb, const ros::SubscriberStatusCallback &info_disconnect_cb, const ros::VoidPtr &tracked_object, bool latch) | |
Private Attributes | |
ImplPtr | impl_ |
Friends | |
class | ImageTransport |
Manages advertisements for publishing camera images.
CameraPublisher is a convenience class for publishing synchronized image and camera info 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, CameraSubscriber simplifies subscribing to camera images.
A CameraPublisher should always be created through a call to ImageTransport::advertiseCamera(), or copied from one that was. Once all copies of a specific CameraPublisher go out of scope, any subscriber callbacks associated with that handle will stop being called. Once all CameraPublisher for a given base topic go out of scope the topic (and all subtopics) will be unadvertised.
Definition at line 62 of file camera_publisher.h.
typedef boost::shared_ptr<Impl> image_transport::CameraPublisher::ImplPtr [private] |
Definition at line 124 of file camera_publisher.h.
typedef boost::weak_ptr<Impl> image_transport::CameraPublisher::ImplWPtr [private] |
Definition at line 126 of file camera_publisher.h.
image_transport::CameraPublisher::CameraPublisher | ( | ) | [inline] |
Definition at line 65 of file camera_publisher.h.
image_transport::CameraPublisher::CameraPublisher | ( | ImageTransport & | image_it, |
ros::NodeHandle & | info_nh, | ||
const std::string & | base_topic, | ||
uint32_t | queue_size, | ||
const SubscriberStatusCallback & | image_connect_cb, | ||
const SubscriberStatusCallback & | image_disconnect_cb, | ||
const ros::SubscriberStatusCallback & | info_connect_cb, | ||
const ros::SubscriberStatusCallback & | info_disconnect_cb, | ||
const ros::VoidPtr & | tracked_object, | ||
bool | latch | ||
) | [private] |
Definition at line 72 of file camera_publisher.cpp.
std::string image_transport::CameraPublisher::getInfoTopic | ( | ) | const |
Returns the camera info topic of this CameraPublisher.
Definition at line 105 of file camera_publisher.cpp.
uint32_t image_transport::CameraPublisher::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 92 of file camera_publisher.cpp.
std::string image_transport::CameraPublisher::getTopic | ( | ) | const |
Returns the base (image) topic of this CameraPublisher.
Definition at line 99 of file camera_publisher.cpp.
image_transport::CameraPublisher::operator void * | ( | ) | const |
Definition at line 155 of file camera_publisher.cpp.
bool image_transport::CameraPublisher::operator!= | ( | const CameraPublisher & | rhs | ) | const [inline] |
Definition at line 112 of file camera_publisher.h.
bool image_transport::CameraPublisher::operator< | ( | const CameraPublisher & | rhs | ) | const [inline] |
Definition at line 111 of file camera_publisher.h.
bool image_transport::CameraPublisher::operator== | ( | const CameraPublisher & | rhs | ) | const [inline] |
Definition at line 113 of file camera_publisher.h.
void image_transport::CameraPublisher::publish | ( | const sensor_msgs::Image & | image, |
const sensor_msgs::CameraInfo & | info | ||
) | const |
Publish an (image, info) pair on the topics associated with this CameraPublisher.
Definition at line 111 of file camera_publisher.cpp.
void image_transport::CameraPublisher::publish | ( | const sensor_msgs::ImageConstPtr & | image, |
const sensor_msgs::CameraInfoConstPtr & | info | ||
) | const |
Publish an (image, info) pair on the topics associated with this CameraPublisher.
Definition at line 122 of file camera_publisher.cpp.
void image_transport::CameraPublisher::publish | ( | sensor_msgs::Image & | image, |
sensor_msgs::CameraInfo & | info, | ||
ros::Time | stamp | ||
) | const |
Publish an (image, info) pair with given timestamp on the topics associated with this CameraPublisher.
Convenience version, which sets the timestamps of both image and info to stamp before publishing.
Definition at line 134 of file camera_publisher.cpp.
Shutdown the advertisements associated with this Publisher.
Definition at line 147 of file camera_publisher.cpp.
friend class ImageTransport [friend] |
Definition at line 130 of file camera_publisher.h.
Definition at line 128 of file camera_publisher.h.