camera_subscriber.cpp
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 
22 
23 namespace fkie_message_filters
24 {
25 
26 CameraSubscriber::CameraSubscriber(const image_transport::ImageTransport& it, const std::string& base_topic, uint32_t queue_size, const image_transport::TransportHints& transport_hints) noexcept
27 {
28  set_subscribe_options(it, base_topic, queue_size, transport_hints);
29  subscribe();
30 }
31 
32 void CameraSubscriber::set_subscribe_options(const image_transport::ImageTransport& it, const std::string& base_topic, uint32_t queue_size, const image_transport::TransportHints& transport_hints) noexcept
33 {
34  it_ = std::make_shared<image_transport::ImageTransport>(it);
35  base_topic_ = base_topic;
36  queue_size_ = queue_size;
37  hints_ = transport_hints;
38 }
39 
40 void CameraSubscriber::subscribe(const image_transport::ImageTransport& it, const std::string& base_topic, uint32_t queue_size, const image_transport::TransportHints& transport_hints) noexcept
41 {
42  set_subscribe_options(it, base_topic, queue_size, transport_hints);
43  subscribe();
44 }
45 
46 std::string CameraSubscriber::topic() const noexcept
47 {
48  return sub_.getTopic();
49 }
50 
51 bool CameraSubscriber::is_configured() const noexcept
52 {
53  return it_ && !base_topic_.empty();
54 }
55 
57 {
58  if (!sub_)
59  {
60  sub_ = it_->subscribeCamera(
62  [this](const sensor_msgs::ImageConstPtr& img, const sensor_msgs::CameraInfoConstPtr& info)
63  {
64  this->cb(img, info);
65  },
67  );
68  }
69 }
70 
72 {
73  sub_.shutdown();
74 }
75 
76 void CameraSubscriber::cb (const sensor_msgs::ImageConstPtr& img, const sensor_msgs::CameraInfoConstPtr& info)
77 {
78  send(img, info);
79 }
80 
81 } // namespace fkie_message_filters
image_transport::CameraSubscriber sub_
void cb(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &)
virtual void unsubscribe_impl() noexcept override
Shut the ROS subscriber down.
virtual void subscribe()
Subscribe to the configured ROS topic.
image_transport::TransportHints hints_
void subscribe()
virtual bool is_configured() const noexcept override
Check if the ROS subscriber is properly configured.
Primary namespace.
Definition: buffer.h:33
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.
CameraSubscriber() noexcept
Constructs an empty subscriber.
virtual std::string topic() const noexcept override
Return the configured ROS topic.
std::shared_ptr< image_transport::ImageTransport > it_
virtual void subscribe_impl() noexcept override
Create a ROS subscriber.
void send(const Outputs &... out)
Pass data to all connected sinks.
Definition: source_impl.h:51
boost::shared_ptr< void > VoidPtr


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