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. More... | |
std::string | getTopic () const |
Returns the base topic of this Publisher. More... | |
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. More... | |
void | publish (const sensor_msgs::ImageConstPtr &message) const |
Publish an image on the topics associated with this Publisher. More... | |
Publisher () | |
void | shutdown () |
Shutdown the advertisements associated with this Publisher. More... | |
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 96 of file publisher.h.
|
private |
Definition at line 173 of file publisher.h.
|
private |
Definition at line 175 of file publisher.h.
|
inline |
Definition at line 131 of file publisher.h.
|
private |
Definition at line 132 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 176 of file publisher.cpp.
std::string image_transport::Publisher::getTopic | ( | ) | const |
Returns the base topic of this Publisher.
Definition at line 182 of file publisher.cpp.
image_transport::Publisher::operator void * | ( | ) | const |
Definition at line 222 of file publisher.cpp.
|
inline |
Definition at line 163 of file publisher.h.
|
inline |
Definition at line 162 of file publisher.h.
|
inline |
Definition at line 164 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 188 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 201 of file publisher.cpp.
|
private |
Definition at line 235 of file publisher.cpp.
void image_transport::Publisher::shutdown | ( | ) |
Shutdown the advertisements associated with this Publisher.
Definition at line 214 of file publisher.cpp.
|
staticprivate |
Definition at line 227 of file publisher.cpp.
|
friend |
Definition at line 185 of file publisher.h.
|
private |
Definition at line 177 of file publisher.h.