publisher.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_H_
21 #define INCLUDE_FKIE_MESSAGE_FILTERS_PUBLISHER_H_
22 
23 
24 #include "source.h"
25 #include "publisher_base.h"
26 #include "message_translate.h"
27 #include <ros/node_handle.h>
28 #include <ros/publisher.h>
29 
30 namespace fkie_message_filters
31 {
32 
50 template<class M, template<typename> class Translate = RosMessageEvent>
51 class Publisher : public PublisherBase, public Sink<typename Translate<M>::FilterType>
52 {
53 public:
60  Publisher() noexcept;
67  Publisher(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size, bool latch = false, ros::CallbackQueueInterface* callback_queue = nullptr) noexcept;
72  virtual bool is_active() const noexcept override;
77  virtual std::string topic() const noexcept override;
91  void advertise(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size, bool latch = false, ros::CallbackQueueInterface* callback_queue = nullptr) noexcept;
108  void advertise(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size, const ros::SubscriberStatusCallback& connect_cb, const ros::SubscriberStatusCallback& disconnect_cb = ros::SubscriberStatusCallback(), const ros::VoidConstPtr& tracked_object = ros::VoidConstPtr(), bool latch = false, ros::CallbackQueueInterface* callback_queue = nullptr) noexcept;
109 
110 protected:
112  virtual void receive (const typename Translate<M>::FilterType& t) noexcept override;
113 private:
114  ros::Publisher pub_;
115 };
116 
117 } // namespace fkie_message_filters
118 
119 #include "publisher_impl.h"
120 
121 #endif /* INCLUDE_FKIE_MESSAGE_FILTERS_PUBLISHER_H_ */
fkie_message_filters
Definition: buffer.h:33
node_handle.h
boost::shared_ptr< void const >
ros
fkie_message_filters::Publisher::advertise
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.
Definition: publisher_impl.h:71
publisher.h
source.h
fkie_message_filters::Publisher::receive
virtual void receive(const typename Translate< M >::FilterType &t) noexcept override
Definition: publisher_impl.h:114
message_translate.h
fkie_message_filters::Publisher::pub_
ros::Publisher pub_
Definition: publisher.h:150
std
fkie_message_filters::Publisher::topic
virtual std::string topic() const noexcept override
Return the configured ROS topic.
Definition: publisher_impl.h:65
SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
fkie_message_filters::Publisher::Publisher
Publisher() noexcept
Constructs an empty publisher.
Definition: publisher_impl.h:48
fkie_message_filters::Publisher::is_active
virtual bool is_active() const noexcept override
Check if the ROS publisher has at least one subscriber.
Definition: publisher_impl.h:59
publisher_base.h


fkie_message_filters
Author(s): Timo Röhling
autogenerated on Wed Mar 2 2022 00:18:57