camera_publisher.cpp
Go to the documentation of this file.
1 /*********************************************************************
2 * Software License Agreement (BSD License)
3 *
4 * Copyright (c) 2009, Willow Garage, Inc.
5 * All rights reserved.
6 *
7 * Redistribution and use in source and binary forms, with or without
8 * modification, are permitted provided that the following conditions
9 * are met:
10 *
11 * * Redistributions of source code must retain the above copyright
12 * notice, this list of conditions and the following disclaimer.
13 * * Redistributions in binary form must reproduce the above
14 * copyright notice, this list of conditions and the following
15 * disclaimer in the documentation and/or other materials provided
16 * with the distribution.
17 * * Neither the name of the Willow Garage nor the names of its
18 * contributors may be used to endorse or promote products derived
19 * from this software without specific prior written permission.
20 *
21 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS
22 * "AS IS" AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT
23 * LIMITED TO, THE IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS
24 * FOR A PARTICULAR PURPOSE ARE DISCLAIMED. IN NO EVENT SHALL THE
25 * COPYRIGHT OWNER OR CONTRIBUTORS BE LIABLE FOR ANY DIRECT, INDIRECT,
26 * INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL DAMAGES (INCLUDING,
27 * BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR SERVICES;
28 * LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
29 * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT
30 * LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN
31 * ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
32 * POSSIBILITY OF SUCH DAMAGE.
33 *********************************************************************/
34 
37 
38 namespace image_transport {
39 
41 {
42  Impl()
43  : unadvertised_(false)
44  {
45  }
46 
48  {
49  shutdown();
50  }
51 
52  bool isValid() const
53  {
54  return !unadvertised_;
55  }
56 
57  void shutdown()
58  {
59  if (!unadvertised_) {
60  unadvertised_ = true;
63  }
64  }
65 
69  //double constructed_;
70 };
71 
73  const std::string& base_topic, uint32_t queue_size,
74  const SubscriberStatusCallback& image_connect_cb,
75  const SubscriberStatusCallback& image_disconnect_cb,
76  const ros::SubscriberStatusCallback& info_connect_cb,
77  const ros::SubscriberStatusCallback& info_disconnect_cb,
78  const ros::VoidPtr& tracked_object, bool latch)
79  : impl_(new Impl)
80 {
81  // Explicitly resolve name here so we compute the correct CameraInfo topic when the
82  // image topic is remapped (#4539).
83  std::string image_topic = info_nh.resolveName(base_topic);
84  std::string info_topic = getCameraInfoTopic(image_topic);
85 
86  impl_->image_pub_ = image_it.advertise(image_topic, queue_size, image_connect_cb,
87  image_disconnect_cb, tracked_object, latch);
88  impl_->info_pub_ = info_nh.advertise<sensor_msgs::CameraInfo>(info_topic, queue_size, info_connect_cb,
89  info_disconnect_cb, tracked_object, latch);
90 }
91 
93 {
94  if (impl_ && impl_->isValid())
95  return std::max(impl_->image_pub_.getNumSubscribers(), impl_->info_pub_.getNumSubscribers());
96  return 0;
97 }
98 
99 std::string CameraPublisher::getTopic() const
100 {
101  if (impl_) return impl_->image_pub_.getTopic();
102  return std::string();
103 }
104 
105 std::string CameraPublisher::getInfoTopic() const
106 {
107  if (impl_) return impl_->info_pub_.getTopic();
108  return std::string();
109 }
110 
111 void CameraPublisher::publish(const sensor_msgs::Image& image, const sensor_msgs::CameraInfo& info) const
112 {
113  if (!impl_ || !impl_->isValid()) {
114  ROS_ASSERT_MSG(false, "Call to publish() on an invalid image_transport::CameraPublisher");
115  return;
116  }
117 
118  impl_->image_pub_.publish(image);
119  impl_->info_pub_.publish(info);
120 }
121 
122 void CameraPublisher::publish(const sensor_msgs::ImageConstPtr& image,
123  const sensor_msgs::CameraInfoConstPtr& info) const
124 {
125  if (!impl_ || !impl_->isValid()) {
126  ROS_ASSERT_MSG(false, "Call to publish() on an invalid image_transport::CameraPublisher");
127  return;
128  }
129 
130  impl_->image_pub_.publish(image);
131  impl_->info_pub_.publish(info);
132 }
133 
134 void CameraPublisher::publish(sensor_msgs::Image& image, sensor_msgs::CameraInfo& info,
135  ros::Time stamp) const
136 {
137  if (!impl_ || !impl_->isValid()) {
138  ROS_ASSERT_MSG(false, "Call to publish() on an invalid image_transport::CameraPublisher");
139  return;
140  }
141 
142  image.header.stamp = stamp;
143  info.header.stamp = stamp;
144  publish(image, info);
145 }
146 
148 {
149  if (impl_) {
150  impl_->shutdown();
151  impl_.reset();
152  }
153 }
154 
155 CameraPublisher::operator void*() const
156 {
157  return (impl_ && impl_->isValid()) ? (void*)1 : (void*)0;
158 }
159 
160 } //namespace image_transport
Manages advertisements of multiple transport options on an Image topic.
Definition: publisher.h:64
void publish(const sensor_msgs::Image &image, const sensor_msgs::CameraInfo &info) const
Publish an (image, info) pair on the topics associated with this CameraPublisher. ...
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
std::string getInfoTopic() const
Returns the camera info topic of this CameraPublisher.
std::string resolveName(const std::string &name, bool remap=true) const
uint32_t getNumSubscribers() const
Returns the number of subscribers that are currently connected to this CameraPublisher.
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
Advertise an image topic, simple version.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
void shutdown()
Shutdown the advertisements associated with this Publisher.
Definition: publisher.cpp:182
void shutdown()
Shutdown the advertisements associated with this Publisher.
#define ROS_ASSERT_MSG(cond,...)
Publisher advertise(const std::string &topic, uint32_t queue_size, bool latch=false)
IMAGE_TRANSPORT_DECL std::string getCameraInfoTopic(const std::string &base_topic)
Form the camera info topic name, sibling to the base topic.
Advertise and subscribe to image topics.
std::string getTopic() const
Returns the base (image) topic of this CameraPublisher.


image_transport
Author(s): Patrick Mihelich
autogenerated on Sat Apr 4 2020 03:14:58