20 #ifndef INCLUDE_FKIE_MESSAGE_FILTERS_PUBLISHER_IMPL_H_ 21 #define INCLUDE_FKIE_MESSAGE_FILTERS_PUBLISHER_IMPL_H_ 29 template<
class M,
template<
typename>
class Translate>
34 template<
class M,
template<
typename>
class Translate>
37 advertise(nh, topic, queue_size, latch, callback_queue);
40 template<
class M,
template<
typename>
class Translate>
43 return pub_.getNumSubscribers() > 0;
46 template<
class M,
template<
typename>
class Translate>
49 return pub_.getTopic();
52 template<
class M,
template<
typename>
class Translate>
56 opts.
init<M>(topic, queue_size,
59 this->update_subscriber_state();
63 this->update_subscriber_state();
68 pub_ = nh.advertise(opts);
69 update_subscriber_state();
72 template<
class M,
template<
typename>
class Translate>
76 opts.
init<M>(topic, queue_size,
79 this->update_subscriber_state();
80 if (connect_cb) connect_cb(ssp);
84 this->update_subscriber_state();
85 if (disconnect_cb) disconnect_cb(ssp);
91 pub_ = nh.advertise(opts);
92 update_subscriber_state();
95 template<
class M,
template<
typename>
class Translate>
98 pub_.publish(Translate<M>::filterToPublish(m));
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void init(const std::string &_topic, uint32_t _queue_size, const SubscriberStatusCallback &_connect_cb=SubscriberStatusCallback(), const SubscriberStatusCallback &_disconnect_cb=SubscriberStatusCallback())
void advertise(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, bool latch=false, ros::CallbackQueueInterface *callback_queue=nullptr) noexcept
Advertise ROS topic.
virtual void receive(const typename Translate< M >::FilterType &t) noexcept override
VoidConstPtr tracked_object
virtual std::string topic() const noexcept override
Return the configured ROS topic.
CallbackQueueInterface * callback_queue
virtual bool is_active() const noexcept override
Check if the ROS publisher has at least one subscriber.
Publisher() noexcept
Constructs an empty publisher.