Manages advertisements of multiple transport options on an Image topic. More...
#include <publisher.h>
Classes | |
struct | Impl |
Public Member Functions | |
uint32_t | getNumSubscribers () const |
Returns the number of subscribers that are currently connected to this Publisher. | |
std::string | getTopic () const |
Returns the base topic of this Publisher. | |
operator void * () const | |
bool | operator!= (const Publisher &rhs) const |
bool | operator< (const Publisher &rhs) const |
bool | operator== (const Publisher &rhs) const |
void | publish (const sensor_msgs::Image &message) const |
Publish an image on the topics associated with this Publisher. | |
void | publish (const sensor_msgs::ImageConstPtr &message) const |
Publish an image on the topics associated with this Publisher. | |
Publisher () | |
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 | |
Publisher (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const SubscriberStatusCallback &connect_cb, const SubscriberStatusCallback &disconnect_cb, const ros::VoidPtr &tracked_object, bool latch, const PubLoaderPtr &loader) | |
SubscriberStatusCallback | rebindCB (const SubscriberStatusCallback &user_cb) |
Static Private Member Functions | |
static void | weakSubscriberCb (const ImplWPtr &impl_wptr, const SingleSubscriberPublisher &plugin_pub, const SubscriberStatusCallback &user_cb) |
Private Attributes | |
ImplPtr | impl_ |
Friends | |
class | ImageTransport |
Manages advertisements of multiple transport options on an Image topic.
Publisher is a drop-in replacement for ros::Publisher when publishing Image topics. In a minimally built environment, they behave the same; however, Publisher is extensible via plugins to publish alternative representations of the image on related subtopics. This is especially useful for limiting bandwidth and latency over a network connection, when you might (for example) use the theora plugin to transport the images as streamed video. All topics are published only on demand (i.e. if there are subscribers).
A Publisher should always be created through a call to ImageTransport::advertise(), or copied from one that was. Once all copies of a specific Publisher go out of scope, any subscriber callbacks associated with that handle will stop being called. Once all Publisher for a given base topic go out of scope the topic (and all subtopics) will be unadvertised.
Definition at line 63 of file publisher.h.
typedef boost::shared_ptr<Impl> image_transport::Publisher::ImplPtr [private] |
Definition at line 108 of file publisher.h.
typedef boost::weak_ptr<Impl> image_transport::Publisher::ImplWPtr [private] |
Definition at line 110 of file publisher.h.
image_transport::Publisher::Publisher | ( | ) | [inline] |
Definition at line 66 of file publisher.h.
image_transport::Publisher::Publisher | ( | ros::NodeHandle & | nh, |
const std::string & | base_topic, | ||
uint32_t | queue_size, | ||
const SubscriberStatusCallback & | connect_cb, | ||
const SubscriberStatusCallback & | disconnect_cb, | ||
const ros::VoidPtr & | tracked_object, | ||
bool | latch, | ||
const PubLoaderPtr & | loader | ||
) | [private] |
Definition at line 100 of file publisher.cpp.
uint32_t image_transport::Publisher::getNumSubscribers | ( | ) | const |
Returns the number of subscribers that are currently connected to this Publisher.
Returns the total number of subscribers to all advertised topics.
Definition at line 130 of file publisher.cpp.
std::string image_transport::Publisher::getTopic | ( | ) | const |
Returns the base topic of this Publisher.
Definition at line 136 of file publisher.cpp.
image_transport::Publisher::operator void * | ( | ) | const |
Definition at line 176 of file publisher.cpp.
bool image_transport::Publisher::operator!= | ( | const Publisher & | rhs | ) | const [inline] |
Definition at line 98 of file publisher.h.
bool image_transport::Publisher::operator< | ( | const Publisher & | rhs | ) | const [inline] |
Definition at line 97 of file publisher.h.
bool image_transport::Publisher::operator== | ( | const Publisher & | rhs | ) | const [inline] |
Definition at line 99 of file publisher.h.
void image_transport::Publisher::publish | ( | const sensor_msgs::Image & | message | ) | const |
Publish an image on the topics associated with this Publisher.
Definition at line 142 of file publisher.cpp.
void image_transport::Publisher::publish | ( | const sensor_msgs::ImageConstPtr & | message | ) | const |
Publish an image on the topics associated with this Publisher.
Definition at line 155 of file publisher.cpp.
SubscriberStatusCallback image_transport::Publisher::rebindCB | ( | const SubscriberStatusCallback & | user_cb | ) | [private] |
Definition at line 189 of file publisher.cpp.
void image_transport::Publisher::shutdown | ( | ) |
Shutdown the advertisements associated with this Publisher.
Definition at line 168 of file publisher.cpp.
void image_transport::Publisher::weakSubscriberCb | ( | const ImplWPtr & | impl_wptr, |
const SingleSubscriberPublisher & | plugin_pub, | ||
const SubscriberStatusCallback & | user_cb | ||
) | [static, private] |
Definition at line 181 of file publisher.cpp.
friend class ImageTransport [friend] |
Definition at line 120 of file publisher.h.
ImplPtr image_transport::Publisher::impl_ [private] |
Definition at line 112 of file publisher.h.