subscriber_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_SUBSCRIBER_IMPL_H_
21 #define INCLUDE_FKIE_MESSAGE_FILTERS_SUBSCRIBER_IMPL_H_
22 
23 #include "subscriber.h"
24 
25 namespace fkie_message_filters
26 {
27 
28 template<class M, template<typename > class Translate>
30 {
31 }
32 
33 template<class M, template<typename > class Translate>
34 Subscriber<M, Translate>::Subscriber(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size, const ros::TransportHints& transport_hints, ros::CallbackQueueInterface* callback_queue) noexcept
35 {
36  subscribe(nh, topic, queue_size, transport_hints, callback_queue);
37 }
38 
39 template<class M, template<typename > class Translate>
40 std::string Subscriber<M, Translate>::topic() const noexcept
41 {
42  return sub_.getTopic();
43 }
44 
45 template<class M, template<typename > class Translate>
46 void Subscriber<M, Translate>::set_subscribe_options(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size, const ros::TransportHints& transport_hints, ros::CallbackQueueInterface* callback_queue) noexcept
47 {
48  unsubscribe();
49  if (!topic.empty())
50  {
51  opts_.initByFullCallbackType<const EventType&>(topic, queue_size, std::bind(&Subscriber<M, Translate>::cb, this, std::placeholders::_1));
52  opts_.callback_queue = callback_queue;
53  opts_.transport_hints = transport_hints;
54  nh_ = std::make_shared<ros::NodeHandle>(nh);
55  }
56 }
57 
58 template<class M, template<typename > class Translate>
59 void Subscriber<M, Translate>::subscribe(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size,
60  const ros::TransportHints& transport_hints, ros::CallbackQueueInterface* callback_queue) noexcept
61 {
62  set_subscribe_options(nh, topic, queue_size, transport_hints, callback_queue);
63  subscribe();
64 }
65 
66 template<class M, template<typename > class Translate>
67 bool Subscriber<M, Translate>::is_configured() const noexcept
68 {
69  return nh_ && !opts_.topic.empty();
70 }
71 
72 template<class M, template<typename > class Translate>
74 {
75  if (!sub_)
76  {
77  sub_ = nh_->subscribe(opts_);
78  }
79 }
80 
81 template<class M, template<typename > class Translate>
83 {
84  sub_.shutdown();
85 }
86 
87 template<class M, template<typename > class Translate>
88 void Subscriber<M, Translate>::cb(const EventType& event)
89 {
90  this->send(Translate<M>::eventToFilter(event));
91 }
92 
93 } // namespace fkie_message_filters
94 
95 #endif /* INCLUDE_FKIE_MESSAGE_FILTERS_SUBSCRIBER_IMPL_H_ */
fkie_message_filters
Definition: buffer.h:33
ros::TransportHints
fkie_message_filters::Subscriber::Subscriber
Subscriber() noexcept
Constructs an empty subscriber.
Definition: subscriber_impl.h:47
fkie_message_filters::Subscriber
Subscribe to a ROS topic as data provider.
Definition: subscriber.h:72
subscriber.h
fkie_message_filters::Subscriber::unsubscribe_impl
virtual void unsubscribe_impl() noexcept override
Shut the ROS subscriber down.
Definition: subscriber_impl.h:100
fkie_message_filters::Subscriber::is_configured
virtual bool is_configured() const noexcept override
Check if the ROS subscriber is properly configured.
Definition: subscriber_impl.h:85
fkie_message_filters::Subscriber::set_subscribe_options
void set_subscribe_options(ros::NodeHandle &nh, const std::string &topic, uint32_t queue_size, const ros::TransportHints &transport_hints=ros::TransportHints(), ros::CallbackQueueInterface *callback_queue=nullptr) noexcept
Configure ROS topic that is to be subscribed.
Definition: subscriber_impl.h:64
fkie_message_filters::Subscriber::cb
void cb(const EventType &event)
Definition: subscriber_impl.h:106
fkie_message_filters::Subscriber::topic
virtual std::string topic() const noexcept override
Return the subscribed topic name.
Definition: subscriber_impl.h:58
fkie_message_filters::SubscriberBase::subscribe
virtual void subscribe()
Subscribe to the configured ROS topic.
Definition: publisher_subscriber_base.cpp:64
fkie_message_filters::Subscriber::subscribe_impl
virtual void subscribe_impl() noexcept override
Create a ROS subscriber.
Definition: subscriber_impl.h:91
fkie_message_filters::Subscriber::EventType
typename Translate< M >::EventType EventType
Definition: subscriber.h:161
ros::CallbackQueueInterface
ros::NodeHandle


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