publisher.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/shared_ptr.hpp>
46 #include <boost/weak_ptr.hpp>
47 
48 #include <ros/forwards.h>
49 #include <ros/node_handle.h>
50 #include <sensor_msgs/PointCloud2.h>
51 
54 
55 namespace point_cloud_transport
56 {
57 
58 class Publisher
59 {
60 public:
62  Publisher();
63 
65  uint32_t getNumSubscribers() const;
66 
68  std::string getTopic() const;
69 
71  void publish(const sensor_msgs::PointCloud2& message) const;
72 
74  void publish(const sensor_msgs::PointCloud2ConstPtr& message) const;
75 
77  void shutdown();
78 
79  operator void*() const;
80 
82  {
83  return impl_ < rhs.impl_;
84  }
85 
87  {
88  return impl_ != rhs.impl_;
89  }
90 
92  {
93  return impl_ == rhs.impl_;
94  }
95 
96 private:
97  Publisher(ros::NodeHandle& nh, const std::string& base_topic, uint32_t queue_size,
100  const ros::VoidPtr& tracked_object, bool latch,
102 
103  struct Impl;
105  typedef boost::weak_ptr<Impl> ImplWPtr;
106 
108 
109  static void weakSubscriberCb(const ImplWPtr& impl_wptr,
112 
115 
116  friend class PointCloudTransport;
117 };
118 
119 }
forwards.h
node_handle.h
point_cloud_transport::Publisher::getTopic
std::string getTopic() const
get base topic of this Publisher
single_subscriber_publisher.h
boost::shared_ptr< void >
point_cloud_transport::Publisher::Publisher
Publisher()
Constructor.
point_cloud_transport::SubscriberStatusCallback
boost::function< void(const SingleSubscriberPublisher &)> SubscriberStatusCallback
Definition: single_subscriber_publisher.h:82
point_cloud_transport::Publisher::shutdown
void shutdown()
Shutdown the advertisements associated with this Publisher.
point_cloud_transport::Publisher::ImplPtr
boost::shared_ptr< Impl > ImplPtr
Definition: publisher.h:103
point_cloud_transport::Publisher::operator<
bool operator<(const point_cloud_transport::Publisher &rhs) const
Definition: publisher.h:81
loader_fwds.h
point_cloud_transport
Definition: exception.h:46
point_cloud_transport::Publisher::ImplWPtr
boost::weak_ptr< Impl > ImplWPtr
Definition: publisher.h:105
point_cloud_transport::Publisher::impl_
ImplPtr impl_
Definition: publisher.h:107
point_cloud_transport::Publisher
Definition: publisher.h:58
point_cloud_transport::Publisher::weakSubscriberCb
static void weakSubscriberCb(const ImplWPtr &impl_wptr, const point_cloud_transport::SingleSubscriberPublisher &plugin_pub, const point_cloud_transport::SubscriberStatusCallback &user_cb)
point_cloud_transport::Publisher::rebindCB
point_cloud_transport::SubscriberStatusCallback rebindCB(const point_cloud_transport::SubscriberStatusCallback &user_cb)
point_cloud_transport::PointCloudTransport
Definition: point_cloud_transport.h:108
point_cloud_transport::SingleSubscriberPublisher
Allows publication of a point cloud to a single subscriber. Only available inside subscriber connecti...
Definition: single_subscriber_publisher.h:54
point_cloud_transport::Publisher::publish
void publish(const sensor_msgs::PointCloud2 &message) const
Publish a point cloud on the topics associated with this Publisher.
point_cloud_transport::Publisher::operator!=
bool operator!=(const point_cloud_transport::Publisher &rhs) const
Definition: publisher.h:86
point_cloud_transport::Publisher::operator==
bool operator==(const point_cloud_transport::Publisher &rhs) const
Definition: publisher.h:91
point_cloud_transport::Publisher::getNumSubscribers
uint32_t getNumSubscribers() const
get total number of subscribers to all advertised topics.
ros::NodeHandle


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