subscriber.h
Go to the documentation of this file.
1 // SPDX-License-Identifier: BSD-3-Clause
2 // SPDX-FileCopyrightText: Czech Technical University in Prague .. 2019, paplhjak .. 2009, Willow Garage, Inc.
3 
4 /*
5  *
6  * BSD 3-Clause License
7  *
8  * Copyright (c) Czech Technical University in Prague
9  * Copyright (c) 2019, paplhjak
10  * Copyright (c) 2009, Willow Garage, Inc.
11  *
12  * All rights reserved.
13  *
14  * Redistribution and use in source and binary forms, with or without
15  * modification, are permitted provided that the following conditions are met:
16  *
17  * 1. Redistributions of source code must retain the above copyright notice, this
18  * list of conditions and the following disclaimer.
19  *
20  * 2. Redistributions in binary form must reproduce the above copyright notice,
21  * this list of conditions and the following disclaimer in the documentation
22  * and/or other materials provided with the distribution.
23  *
24  * 3. Neither the name of the copyright holder nor the names of its
25  * contributors may be used to endorse or promote products derived from
26  * this software without specific prior written permission.
27  *
28  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
29  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
30  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
31  * DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
32  * FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
33  * DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
34  * SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
35  * CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
36  * OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
37  * OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
38  *
39  */
40 
41 #pragma once
42 
43 #include <string>
44 
45 #include <boost/function.hpp>
46 #include <boost/shared_ptr.hpp>
47 #include <boost/weak_ptr.hpp>
48 
49 #include <ros/forwards.h>
50 #include <ros/node_handle.h>
51 #include <sensor_msgs/PointCloud2.h>
52 
55 
56 namespace point_cloud_transport {
57 
74 {
75 public:
76  Subscriber();
77 
84  std::string getTopic() const;
85 
89  uint32_t getNumPublishers() const;
90 
94  std::string getTransport() const;
95 
99  void shutdown();
100 
101  operator void*() const;
102 
104  {
105  return impl_ < rhs.impl_;
106  }
107 
109  {
110  return impl_ != rhs.impl_;
111  }
112 
114  {
115  return impl_ == rhs.impl_;
116  }
117 
118 private:
119  Subscriber(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
120  const boost::function<void(const sensor_msgs::PointCloud2ConstPtr&)>& callback,
121  const ros::VoidPtr& tracked_object, const point_cloud_transport::TransportHints& transport_hints,
122  bool allow_concurrent_callbacks, const point_cloud_transport::SubLoaderPtr& loader);
123 
124  struct Impl;
126  typedef boost::weak_ptr<Impl> ImplWPtr;
127 
129 
130  friend class PointCloudTransport;
131 };
132 
133 }
forwards.h
node_handle.h
point_cloud_transport::Subscriber::getNumPublishers
uint32_t getNumPublishers() const
transport_hints.h
point_cloud_transport::TransportHints
Stores transport settings for a point cloud topic subscription.
Definition: transport_hints.h:52
boost::shared_ptr< void >
point_cloud_transport::Subscriber::impl_
ImplPtr impl_
Definition: subscriber.h:128
point_cloud_transport::Subscriber
Definition: subscriber.h:73
loader_fwds.h
point_cloud_transport::Subscriber::operator<
bool operator<(const point_cloud_transport::Subscriber &rhs) const
Definition: subscriber.h:103
point_cloud_transport::Subscriber::getTopic
std::string getTopic() const
point_cloud_transport
Definition: exception.h:46
point_cloud_transport::Subscriber::ImplPtr
boost::shared_ptr< Impl > ImplPtr
Definition: subscriber.h:124
point_cloud_transport::Subscriber::operator!=
bool operator!=(const point_cloud_transport::Subscriber &rhs) const
Definition: subscriber.h:108
point_cloud_transport::Subscriber::operator==
bool operator==(const point_cloud_transport::Subscriber &rhs) const
Definition: subscriber.h:113
point_cloud_transport::PointCloudTransport
Definition: point_cloud_transport.h:108
point_cloud_transport::Subscriber::Subscriber
Subscriber()
point_cloud_transport::Subscriber::getTransport
std::string getTransport() const
point_cloud_transport::Subscriber::shutdown
void shutdown()
ros::NodeHandle
point_cloud_transport::Subscriber::ImplWPtr
boost::weak_ptr< Impl > ImplWPtr
Definition: subscriber.h:126


point_cloud_transport
Author(s): Jakub Paplham
autogenerated on Sat Jun 17 2023 02:48:44