Go to the documentation of this file.
35 #ifndef IMAGE_TRANSPORT_SIMPLE_PUBLISHER_PLUGIN_H
36 #define IMAGE_TRANSPORT_SIMPLE_PUBLISHER_PLUGIN_H
39 #include <boost/scoped_ptr.hpp>
61 class SimplePublisherPlugin :
public PublisherPlugin
78 virtual void publish(
const sensor_msgs::Image& message)
const
81 ROS_ASSERT_MSG(
false,
"Call to publish() on an invalid image_transport::SimplePublisherPlugin");
105 tracked_object, latch);
109 typedef boost::function<void(
const M&)>
PublishFn;
119 virtual void publish(
const sensor_msgs::Image& message,
const PublishFn& publish_fn)
const = 0;
166 struct SimplePublisherPluginImpl
177 boost::scoped_ptr<SimplePublisherPluginImpl>
simple_impl_;
205 internal_cb(ros_ssp);
220 typedef boost::function<void(
const sensor_msgs::Image&)>
ImagePublishFn;
228 template <
class PubT>
232 typedef void (PubT::*InternalPublishMemFn)(
const M&)
const;
233 InternalPublishMemFn internal_pub_mem_fn = &PubT::publish;
234 return boost::bind(internal_pub_mem_fn, &pub, boost::placeholders::_1);
void(SimplePublisherPlugin::* SubscriberStatusMemFn)(const ros::SingleSubscriberPublisher &pub)
PublishFn bindInternalPublisher(const PubT &pub) const
virtual std::string getTransportName() const =0
Get a string identifier for the transport provided by this plugin.
virtual void advertiseImpl(ros::NodeHandle &nh, const std::string &base_topic, uint32_t queue_size, const SubscriberStatusCallback &user_connect_cb, const SubscriberStatusCallback &user_disconnect_cb, const ros::VoidPtr &tracked_object, bool latch)
Advertise a topic. Must be implemented by the subclass.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
const ros::Publisher & getPublisher() const
Returns the internal ros::Publisher.
boost::function< void(const sensor_msgs::Image &)> ImagePublishFn
Publisher advertise(AdvertiseOptions &ops)
virtual void publish(const sensor_msgs::Image &message) const
Publish an image using the transport associated with this PublisherPlugin.
#define ROS_ASSERT_MSG(cond,...)
virtual void connectCallback(const ros::SingleSubscriberPublisher &pub)
Function called when a subscriber connects to the internal publisher.
virtual ~SimplePublisherPlugin()
boost::function< void(const M &)> PublishFn
Generic function for publishing the internal message type.
virtual std::string getTopicToAdvertise(const std::string &base_topic) const
Return the communication topic name for a given base topic.
Allows publication of an image to a single subscriber. Only available inside subscriber connection ca...
virtual std::string getTopic() const
Returns the communication topic that this PublisherPlugin will publish on.
virtual void disconnectCallback(const ros::SingleSubscriberPublisher &pub)
Function called when a subscriber disconnects from the internal publisher.
const ros::NodeHandle & nh() const
Returns the ros::NodeHandle to be used for parameter lookup.
virtual uint32_t getNumSubscribers() const
Returns the number of subscribers that are currently connected to this PublisherPlugin.
void subscriberCB(const ros::SingleSubscriberPublisher &ros_ssp, const SubscriberStatusCallback &user_cb, const ros::SubscriberStatusCallback &internal_cb)
Base class to simplify implementing most plugins to Publisher.
SimplePublisherPluginImpl(const ros::NodeHandle &nh)
boost::scoped_ptr< SimplePublisherPluginImpl > simple_impl_
const ros::NodeHandle param_nh_
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
std::string getSubscriberName() const
ros::SubscriberStatusCallback bindCB(const SubscriberStatusCallback &user_cb, SubscriberStatusMemFn internal_cb_fn)
virtual void shutdown()
Shutdown any advertisements associated with this PublisherPlugin.
image_transport
Author(s): Patrick Mihelich
autogenerated on Sat Jan 20 2024 03:14:50