image_transport.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 
38 #include <pluginlib/class_loader.h>
39 #include <boost/make_shared.hpp>
40 #include <boost/foreach.hpp>
41 #include <boost/algorithm/string/erase.hpp>
42 
43 namespace image_transport {
44 
46 {
50 
51  Impl(const ros::NodeHandle& nh)
52  : nh_(nh),
53  pub_loader_( boost::make_shared<PubLoader>("image_transport", "image_transport::PublisherPlugin") ),
54  sub_loader_( boost::make_shared<SubLoader>("image_transport", "image_transport::SubscriberPlugin") )
55  {
56  }
57 };
58 
60  : impl_(new Impl(nh))
61 {
62 }
63 
65 {
66 }
67 
68 Publisher ImageTransport::advertise(const std::string& base_topic, uint32_t queue_size, bool latch)
69 {
70  return advertise(base_topic, queue_size, SubscriberStatusCallback(),
72 }
73 
74 Publisher ImageTransport::advertise(const std::string& base_topic, uint32_t queue_size,
75  const SubscriberStatusCallback& connect_cb,
76  const SubscriberStatusCallback& disconnect_cb,
77  const ros::VoidPtr& tracked_object, bool latch)
78 {
79  return Publisher(impl_->nh_, base_topic, queue_size, connect_cb, disconnect_cb, tracked_object, latch, impl_->pub_loader_);
80 }
81 
82 Subscriber ImageTransport::subscribe(const std::string& base_topic, uint32_t queue_size,
83  const boost::function<void(const sensor_msgs::ImageConstPtr&)>& callback,
84  const ros::VoidPtr& tracked_object, const TransportHints& transport_hints)
85 {
86  return Subscriber(impl_->nh_, base_topic, queue_size, callback, tracked_object, transport_hints, impl_->sub_loader_);
87 }
88 
89 CameraPublisher ImageTransport::advertiseCamera(const std::string& base_topic, uint32_t queue_size, bool latch)
90 {
91  return advertiseCamera(base_topic, queue_size,
94  ros::VoidPtr(), latch);
95 }
96 
97 CameraPublisher ImageTransport::advertiseCamera(const std::string& base_topic, uint32_t queue_size,
98  const SubscriberStatusCallback& image_connect_cb,
99  const SubscriberStatusCallback& image_disconnect_cb,
100  const ros::SubscriberStatusCallback& info_connect_cb,
101  const ros::SubscriberStatusCallback& info_disconnect_cb,
102  const ros::VoidPtr& tracked_object, bool latch)
103 {
104  return CameraPublisher(*this, impl_->nh_, base_topic, queue_size, image_connect_cb, image_disconnect_cb,
105  info_connect_cb, info_disconnect_cb, tracked_object, latch);
106 }
107 
108 CameraSubscriber ImageTransport::subscribeCamera(const std::string& base_topic, uint32_t queue_size,
109  const CameraSubscriber::Callback& callback,
110  const ros::VoidPtr& tracked_object,
111  const TransportHints& transport_hints)
112 {
113  return CameraSubscriber(*this, impl_->nh_, base_topic, queue_size, callback, tracked_object, transport_hints);
114 }
115 
116 std::vector<std::string> ImageTransport::getDeclaredTransports() const
117 {
118  std::vector<std::string> transports = impl_->sub_loader_->getDeclaredClasses();
119  // Remove the "_sub" at the end of each class name.
120  BOOST_FOREACH(std::string& transport, transports) {
121  transport = boost::erase_last_copy(transport, "_sub");
122  }
123  return transports;
124 }
125 
126 std::vector<std::string> ImageTransport::getLoadableTransports() const
127 {
128  std::vector<std::string> loadableTransports;
129 
130  BOOST_FOREACH( const std::string& transportPlugin, impl_->sub_loader_->getDeclaredClasses() )
131  {
132  // If the plugin loads without throwing an exception, add its
133  // transport name to the list of valid plugins, otherwise ignore
134  // it.
135  try
136  {
137  boost::shared_ptr<image_transport::SubscriberPlugin> sub = impl_->sub_loader_->createInstance(transportPlugin);
138  loadableTransports.push_back(boost::erase_last_copy(transportPlugin, "_sub")); // Remove the "_sub" at the end of each class name.
139  }
140  catch (const pluginlib::LibraryLoadException& e) {}
141  catch (const pluginlib::CreateClassException& e) {}
142  }
143 
144  return loadableTransports;
145 
146 }
147 
148 } //namespace image_transport
Manages advertisements of multiple transport options on an Image topic.
Definition: publisher.h:64
std::vector< std::string > getLoadableTransports() const
Returns the names of all transports that are loadable in the system.
Subscriber subscribe(const std::string &base_topic, uint32_t queue_size, const boost::function< void(const sensor_msgs::ImageConstPtr &)> &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
Subscribe to an image topic, version for arbitrary boost::function object.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
ImageTransport(const ros::NodeHandle &nh)
CameraSubscriber subscribeCamera(const std::string &base_topic, uint32_t queue_size, const CameraSubscriber::Callback &callback, const ros::VoidPtr &tracked_object=ros::VoidPtr(), const TransportHints &transport_hints=TransportHints())
Subscribe to a synchronized image & camera info topic pair, version for arbitrary boost::function obj...
Publisher advertise(const std::string &base_topic, uint32_t queue_size, bool latch=false)
Advertise an image topic, simple version.
Manages advertisements for publishing camera images.
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
Manages a subscription callback on a specific topic that can be interpreted as an Image topic...
Definition: subscriber.h:62
Manages a subscription callback on synchronized Image and CameraInfo topics.
CameraPublisher advertiseCamera(const std::string &base_topic, uint32_t queue_size, bool latch=false)
Advertise a synchronized camera raw image + info topic pair, simple version.
std::vector< std::string > getDeclaredTransports() const
Returns the names of all transports declared in the system. Declared transports are not necessarily b...
boost::function< void(const sensor_msgs::ImageConstPtr &, const sensor_msgs::CameraInfoConstPtr &)> Callback
Stores transport settings for an image topic subscription.


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