#include <resized_publisher.h>
|
virtual std::string | getTransportName () const |
| Get a string identifier for the transport provided by this plugin. More...
|
|
virtual uint32_t | getNumSubscribers () const |
| Returns the number of subscribers that are currently connected to this PublisherPlugin. More...
|
|
virtual std::string | getTopic () const |
| Returns the communication topic that this PublisherPlugin will publish on. More...
|
|
virtual void | publish (const sensor_msgs::Image &message) const |
| Publish an image using the transport associated with this PublisherPlugin. More...
|
|
virtual void | shutdown () |
| Shutdown any advertisements associated with this PublisherPlugin. More...
|
|
virtual | ~SimplePublisherPlugin () |
|
void | advertise (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, bool latch=true) |
| Advertise a topic, simple version. More...
|
|
void | advertise (ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const SubscriberStatusCallback &connect_cb, const SubscriberStatusCallback &disconnect_cb=SubscriberStatusCallback(), const ros::VoidPtr &tracked_object=ros::VoidPtr(), bool latch=true) |
| Advertise a topic with subscriber status callbacks. More...
|
|
virtual void | publish (const sensor_msgs::ImageConstPtr &message) const |
| Publish an image using the transport associated with this PublisherPlugin. More...
|
|
virtual void | publish (const sensor_msgs::Image &message, const uint8_t *data) const |
| Publish an image using the transport associated with this PublisherPlugin. This version of the function can be used to optimize cases where you don't want to fill a ROS message first to avoid useless copies. More...
|
|
virtual | ~PublisherPlugin () |
|
|
static std::string | getLookupName (const std::string &transport_name) |
| Return the lookup name of the PublisherPlugin associated with a specific transport identifier. More...
|
|
typedef boost::function< void(const image_transport_tutorial::ResizedImage &)> | PublishFn |
| Generic function for publishing the internal message type. More...
|
|
Definition at line 4 of file resized_publisher.h.
◆ getTransportName()
virtual std::string ResizedPublisher::getTransportName |
( |
| ) |
const |
|
inlinevirtual |
◆ publish()
void ResizedPublisher::publish |
( |
const sensor_msgs::Image & |
message, |
|
|
const PublishFn & |
publish_fn |
|
) |
| const |
|
protectedvirtual |
The documentation for this class was generated from the following files: