image_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 ImagePublisher::ImagePublisher(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 ImagePublisher::is_active() const noexcept
32 {
33  return pub_.getNumSubscribers() > 0;
34 }
35 
36 std::string ImagePublisher::topic() const noexcept
37 {
38  return pub_.getTopic();
39 }
40 
41 void ImagePublisher::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_->advertise(
45  base_topic, queue_size,
47  {
49  },
51  {
53  },
54  ros::VoidPtr(),
55  latch
56  );
58 }
59 
60 void ImagePublisher::advertise (const image_transport::ImageTransport& it, const std::string& base_topic, uint32_t queue_size, const image_transport::SubscriberStatusCallback& connect_cb, const image_transport::SubscriberStatusCallback& disconnect_cb, const ros::VoidPtr& tracked_object, bool latch) noexcept
61 {
62  it_ = std::make_shared<image_transport::ImageTransport>(it);
63  pub_ = it_->advertise(
64  base_topic, queue_size,
65  [this, connect_cb](const image_transport::SingleSubscriberPublisher& ssp)
66  {
68  if (connect_cb) connect_cb(ssp);
69  },
70  [this, disconnect_cb](const image_transport::SingleSubscriberPublisher& ssp)
71  {
73  if (disconnect_cb) disconnect_cb(ssp);
74  },
75  tracked_object,
76  latch
77  );
79 }
80 
81 void ImagePublisher::receive (const sensor_msgs::ImageConstPtr& img) noexcept
82 {
83  pub_.publish(img);
84 }
85 
86 } // namespace fkie_message_filters
std::shared_ptr< image_transport::ImageTransport > it_
uint32_t getNumSubscribers() const
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
ImagePublisher() noexcept
Constructs an empty publisher.
void update_subscriber_state()
Cause all linked subscribers to subscribe or unsubscribe to their ROS topics.
Primary namespace.
Definition: buffer.h:33
virtual bool is_active() const noexcept override
Check if the ROS publisher has at least one subscriber.
void publish(const sensor_msgs::Image &message) const
virtual std::string topic() const noexcept override
Return the configured ROS topic.
void advertise(const image_transport::ImageTransport &it, const std::string &base_topic, uint32_t queue_size, bool latch=false) noexcept
Advertise ROS image topic.
void receive(const sensor_msgs::ImageConstPtr &) noexcept override
image_transport::Publisher pub_
boost::shared_ptr< void > VoidPtr
std::string getTopic() const


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