camera_publisher.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 CameraPublisher::CameraPublisher(const image_transport::ImageTransport& it, const std::string& base_topic, uint32_t queue_size, bool latch) noexcept
27 {
28  advertise(it, base_topic, queue_size, latch);
29 }
30 
31 bool CameraPublisher::is_active() const noexcept
32 {
33  return pub_.getNumSubscribers() > 0;
34 }
35 
36 std::string CameraPublisher::topic() const noexcept
37 {
38  return pub_.getTopic();
39 }
40 
41 void CameraPublisher::advertise(const image_transport::ImageTransport& it, const std::string& base_topic, uint32_t queue_size, bool latch) noexcept
42 {
43  it_ = std::make_shared<image_transport::ImageTransport>(it);
44  pub_ = it_->advertiseCamera(
45  base_topic, queue_size,
47  {
49  },
51  {
53  },
54  [this](const ros::SingleSubscriberPublisher&)
55  {
57  },
58  [this](const ros::SingleSubscriberPublisher&)
59  {
61  },
62  ros::VoidPtr(),
63  latch
64  );
66 }
67 
68 void CameraPublisher::advertise (const image_transport::ImageTransport& it, const std::string& base_topic, uint32_t queue_size, const image_transport::SubscriberStatusCallback& image_connect_cb, const image_transport::SubscriberStatusCallback& image_disconnect_cb, const ros::SubscriberStatusCallback& info_connect_cb, const ros::SubscriberStatusCallback& info_disconnect_cb, const ros::VoidPtr& tracked_object, bool latch) noexcept
69 {
70  it_ = std::make_shared<image_transport::ImageTransport>(it);
71  pub_ = it_->advertiseCamera(
72  base_topic, queue_size,
73  [this, image_connect_cb](const image_transport::SingleSubscriberPublisher& ssp)
74  {
76  if (image_connect_cb) image_connect_cb(ssp);
77  },
78  [this, image_disconnect_cb](const image_transport::SingleSubscriberPublisher& ssp)
79  {
81  if (image_disconnect_cb) image_disconnect_cb(ssp);
82  },
83  [this, info_connect_cb](const ros::SingleSubscriberPublisher& ssp)
84  {
86  if (info_connect_cb) info_connect_cb(ssp);
87  },
88  [this, info_disconnect_cb](const ros::SingleSubscriberPublisher& ssp)
89  {
91  if (info_disconnect_cb) info_disconnect_cb(ssp);
92  },
93  tracked_object,
94  latch
95  );
97 }
98 
99 void CameraPublisher::receive (const sensor_msgs::ImageConstPtr& img, const sensor_msgs::CameraInfoConstPtr& info) noexcept
100 {
101  pub_.publish(img, info);
102 }
103 
104 } // namespace fkie_message_filters
void advertise(const image_transport::ImageTransport &it, const std::string &base_topic, uint32_t queue_size, bool latch=false) noexcept
Advertise ROS camera topic.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void receive(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &) noexcept override
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
std::shared_ptr< image_transport::ImageTransport > it_
std::string getTopic() const
uint32_t getNumSubscribers() const
void update_subscriber_state()
Cause all linked subscribers to subscribe or unsubscribe to their ROS topics.
Primary namespace.
Definition: buffer.h:33
image_transport::CameraPublisher pub_
virtual bool is_active() const noexcept override
Check if the ROS publisher has at least one subscriber.
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
CameraPublisher() noexcept
Constructs an empty publisher.
boost::shared_ptr< void > VoidPtr
virtual std::string topic() const noexcept override
Return the configured ROS topic.


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