camera_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_CAMERA_SUBSCRIBER_H_
21 #define INCLUDE_FKIE_MESSAGE_FILTERS_CAMERA_SUBSCRIBER_H_
22 
23 #include "subscriber_base.h"
24 #include "source.h"
25 #include <sensor_msgs/Image.h>
26 #include <sensor_msgs/CameraInfo.h>
28 
29 namespace fkie_message_filters
30 {
31 
44 class CameraSubscriber : public SubscriberBase, public Source<sensor_msgs::ImageConstPtr, sensor_msgs::CameraInfoConstPtr>
45 {
46 public:
51  CameraSubscriber() noexcept {}
63  CameraSubscriber(const image_transport::ImageTransport& it, const std::string& base_topic, uint32_t queue_size, const image_transport::TransportHints& transport_hints = image_transport::TransportHints()) noexcept;
76  void set_subscribe_options(const image_transport::ImageTransport& it, const std::string& base_topic, uint32_t queue_size, const image_transport::TransportHints& transport_hints = image_transport::TransportHints()) noexcept;
89  void subscribe(const image_transport::ImageTransport& it, const std::string& base_topic, uint32_t queue_size, const image_transport::TransportHints& transport_hints = image_transport::TransportHints()) noexcept;
90  using SubscriberBase::subscribe;
91  using SubscriberBase::unsubscribe;
92  using SubscriberBase::subscribe_on_demand;
97  virtual std::string topic() const noexcept override;
98 protected:
103  virtual bool is_configured() const noexcept override;
108  virtual void subscribe_impl() noexcept override;
113  virtual void unsubscribe_impl() noexcept override;
114 private:
115  void cb(const sensor_msgs::ImageConstPtr&, const sensor_msgs::CameraInfoConstPtr&);
116  std::shared_ptr<image_transport::ImageTransport> it_;
117  std::string base_topic_;
118  uint32_t queue_size_;
119  image_transport::TransportHints hints_;
121 };
122 
123 } // namespace fkie_message_filters
124 
125 #endif /* INCLUDE_FKIE_MESSAGE_FILTERS_CAMERA_SUBSCRIBER_H_ */
fkie_message_filters
Definition: buffer.h:33
subscriber_base.h
image_transport::ImageTransport
fkie_message_filters::SubscriberBase::unsubscribe
virtual void unsubscribe()
Unsubscribe from the configured ROS topic.
Definition: publisher_subscriber_base.cpp:70
fkie_message_filters::CameraSubscriber::CameraSubscriber
CameraSubscriber() noexcept
Constructs an empty subscriber.
Definition: camera_subscriber.h:87
source.h
fkie_message_filters::CameraSubscriber::hints_
image_transport::TransportHints hints_
Definition: camera_subscriber.h:155
fkie_message_filters::CameraSubscriber::unsubscribe_impl
virtual void unsubscribe_impl() noexcept override
Shut the ROS subscriber down.
Definition: camera_subscriber.cpp:89
fkie_message_filters::CameraSubscriber::it_
std::shared_ptr< image_transport::ImageTransport > it_
Definition: camera_subscriber.h:152
fkie_message_filters::CameraSubscriber::set_subscribe_options
void set_subscribe_options(const image_transport::ImageTransport &it, const std::string &base_topic, uint32_t queue_size, const image_transport::TransportHints &transport_hints=image_transport::TransportHints()) noexcept
Configure ROS topic that is to be subscribed.
Definition: camera_subscriber.cpp:50
image_transport.h
fkie_message_filters::CameraSubscriber::queue_size_
uint32_t queue_size_
Definition: camera_subscriber.h:154
fkie_message_filters::CameraSubscriber::sub_
image_transport::CameraSubscriber sub_
Definition: camera_subscriber.h:156
std
fkie_message_filters::CameraSubscriber::subscribe_impl
virtual void subscribe_impl() noexcept override
Create a ROS subscriber.
Definition: camera_subscriber.cpp:74
fkie_message_filters::CameraSubscriber::cb
void cb(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &)
Definition: camera_subscriber.cpp:94
fkie_message_filters::CameraSubscriber::base_topic_
std::string base_topic_
Definition: camera_subscriber.h:153
image_transport
fkie_message_filters::SubscriberBase::subscribe
virtual void subscribe()
Subscribe to the configured ROS topic.
Definition: publisher_subscriber_base.cpp:64
fkie_message_filters::CameraSubscriber::topic
virtual std::string topic() const noexcept override
Return the configured ROS topic.
Definition: camera_subscriber.cpp:64
fkie_message_filters::CameraSubscriber::is_configured
virtual bool is_configured() const noexcept override
Check if the ROS subscriber is properly configured.
Definition: camera_subscriber.cpp:69
image_transport::TransportHints
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
sensor_msgs


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