publisher_impl.h
Go to the documentation of this file.
1 /****************************************************************************
2  *
3  * fkie_message_filters
4  * Copyright © 2018-2020 Fraunhofer FKIE
5  * Author: Timo Röhling
6  *
7  * Licensed under the Apache License, Version 2.0 (the "License");
8  * you may not use this file except in compliance with the License.
9  * You may obtain a copy of the License at
10  *
11  * http://www.apache.org/licenses/LICENSE-2.0
12  *
13  * Unless required by applicable law or agreed to in writing, software
14  * distributed under the License is distributed on an "AS IS" BASIS,
15  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
16  * See the License for the specific language governing permissions and
17  * limitations under the License.
18  *
19  ****************************************************************************/
20 #ifndef INCLUDE_FKIE_MESSAGE_FILTERS_PUBLISHER_IMPL_H_
21 #define INCLUDE_FKIE_MESSAGE_FILTERS_PUBLISHER_IMPL_H_
22 
23 #include "publisher.h"
24 #include <ros/advertise_options.h>
25 
26 namespace fkie_message_filters
27 {
28 
29 template<class M, template<typename> class Translate>
31 {
32 }
33 
34 template<class M, template<typename> class Translate>
35 Publisher<M, Translate>::Publisher(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size, bool latch, ros::CallbackQueueInterface* callback_queue) noexcept
36 {
37  advertise(nh, topic, queue_size, latch, callback_queue);
38 }
39 
40 template<class M, template<typename> class Translate>
42 {
43  return pub_.getNumSubscribers() > 0;
44 }
45 
46 template<class M, template<typename> class Translate>
47 std::string Publisher<M, Translate>::topic() const noexcept
48 {
49  return pub_.getTopic();
50 }
51 
52 template<class M, template<typename> class Translate>
53 void Publisher<M, Translate>::advertise(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size, bool latch, ros::CallbackQueueInterface* callback_queue) noexcept
54 {
56  opts.init<M>(topic, queue_size,
57  [this](const ros::SingleSubscriberPublisher&)
58  {
59  this->update_subscriber_state();
60  },
61  [this](const ros::SingleSubscriberPublisher&)
62  {
63  this->update_subscriber_state();
64  }
65  );
66  opts.latch = latch;
67  opts.callback_queue = callback_queue;
68  pub_ = nh.advertise(opts);
69  update_subscriber_state();
70 }
71 
72 template<class M, template<typename> class Translate>
73 void Publisher<M, Translate>::advertise(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size, const ros::SubscriberStatusCallback& connect_cb, const ros::SubscriberStatusCallback& disconnect_cb, const ros::VoidConstPtr& tracked_object, bool latch, ros::CallbackQueueInterface* callback_queue) noexcept
74 {
76  opts.init<M>(topic, queue_size,
77  [this, connect_cb](const ros::SingleSubscriberPublisher& ssp)
78  {
79  this->update_subscriber_state();
80  if (connect_cb) connect_cb(ssp);
81  },
82  [this, disconnect_cb](const ros::SingleSubscriberPublisher& ssp)
83  {
84  this->update_subscriber_state();
85  if (disconnect_cb) disconnect_cb(ssp);
86  }
87  );
88  opts.latch = latch;
89  opts.callback_queue = callback_queue;
90  opts.tracked_object = tracked_object;
91  pub_ = nh.advertise(opts);
92  update_subscriber_state();
93 }
94 
95 template<class M, template<typename> class Translate>
96 void Publisher<M, Translate>::receive (const typename Translate<M>::FilterType& m) noexcept
97 {
98  pub_.publish(Translate<M>::filterToPublish(m));
99 }
100 
101 } // namespace fkie_message_filters
102 
103 #endif /* INCLUDE_FKIE_MESSAGE_FILTERS_PUBLISHER_IMPL_H_ */
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
Primary namespace.
Definition: buffer.h:33
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.


fkie_message_filters
Author(s): Timo Röhling
autogenerated on Mon Feb 28 2022 22:21:43