subscriber.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_H_
21 #define INCLUDE_FKIE_MESSAGE_FILTERS_SUBSCRIBER_H_
22 
23 #include "source.h"
24 #include "message_translate.h"
25 #include "subscriber_base.h"
26 #include <ros/node_handle.h>
27 #include <ros/subscriber.h>
28 #include <ros/subscribe_options.h>
29 #include <ros/transport_hints.h>
30 #include <memory>
31 
32 namespace fkie_message_filters
33 {
34 
53 template<class M, template<typename> class Translate = RosMessageEvent>
54 class Subscriber : public SubscriberBase, public Source<typename Translate<M>::FilterType>
55 {
56 public:
63  Subscriber() noexcept;
76  Subscriber(ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size, const ros::TransportHints& transport_hints = ros::TransportHints(), ros::CallbackQueueInterface* callback_queue = nullptr) noexcept;
90  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;
103  void subscribe (ros::NodeHandle& nh, const std::string& topic, uint32_t queue_size, const ros::TransportHints& transport_hints = ros::TransportHints(), ros::CallbackQueueInterface* callback_queue = nullptr) noexcept;
104  using SubscriberBase::subscribe;
105  using SubscriberBase::unsubscribe;
106  using SubscriberBase::subscribe_on_demand;
107  virtual std::string topic() const noexcept override;
108 protected:
113  virtual bool is_configured() const noexcept override;
118  virtual void subscribe_impl() noexcept override;
123  virtual void unsubscribe_impl() noexcept override;
124 private:
125  using EventType = typename Translate<M>::EventType;
126  using FilterType = typename Translate<M>::FilterType;
127  void cb(const EventType& event);
129  ros::SubscribeOptions opts_;
130  std::shared_ptr<ros::NodeHandle> nh_;
131 };
132 
133 } // namespace fkie_message_filters
134 
135 #include "subscriber_impl.h"
136 
137 #endif /* INCLUDE_FKIE_MESSAGE_FILTERS_SUBSCRIBER_H_ */
fkie_message_filters
Definition: buffer.h:33
node_handle.h
subscriber_base.h
ros
fkie_message_filters::Subscriber::Subscriber
Subscriber() noexcept
Constructs an empty subscriber.
Definition: subscriber_impl.h:47
fkie_message_filters::SubscriberBase::unsubscribe
virtual void unsubscribe()
Unsubscribe from the configured ROS topic.
Definition: publisher_subscriber_base.cpp:70
fkie_message_filters::Subscriber::unsubscribe_impl
virtual void unsubscribe_impl() noexcept override
Shut the ROS subscriber down.
Definition: subscriber_impl.h:100
source.h
transport_hints.h
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
subscriber.h
fkie_message_filters::Subscriber::opts_
ros::SubscribeOptions opts_
Definition: subscriber.h:165
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
message_translate.h
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::Subscriber::nh_
std::shared_ptr< ros::NodeHandle > nh_
Definition: subscriber.h:166
std
fkie_message_filters::Subscriber::FilterType
typename Translate< M >::FilterType FilterType
Definition: subscriber.h:162
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::sub_
ros::Subscriber sub_
Definition: subscriber.h:164
fkie_message_filters::SubscriberBase::subscribe_on_demand
virtual void subscribe_on_demand(PublisherBase &pub)
Subscribe to the configured ROS topic whenever the given publisher is active.
Definition: publisher_subscriber_base.cpp:76
fkie_message_filters::Subscriber::EventType
typename Translate< M >::EventType EventType
Definition: subscriber.h:161
subscribe_options.h


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