This file is indexed.

/usr/include/ros/publication.h is in libroscpp-dev 1.11.16-3.

This file is owned by root:root, with mode 0o644.

The actual contents of the file can be viewed below.

  1
  2
  3
  4
  5
  6
  7
  8
  9
 10
 11
 12
 13
 14
 15
 16
 17
 18
 19
 20
 21
 22
 23
 24
 25
 26
 27
 28
 29
 30
 31
 32
 33
 34
 35
 36
 37
 38
 39
 40
 41
 42
 43
 44
 45
 46
 47
 48
 49
 50
 51
 52
 53
 54
 55
 56
 57
 58
 59
 60
 61
 62
 63
 64
 65
 66
 67
 68
 69
 70
 71
 72
 73
 74
 75
 76
 77
 78
 79
 80
 81
 82
 83
 84
 85
 86
 87
 88
 89
 90
 91
 92
 93
 94
 95
 96
 97
 98
 99
100
101
102
103
104
105
106
107
108
109
110
111
112
113
114
115
116
117
118
119
120
121
122
123
124
125
126
127
128
129
130
131
132
133
134
135
136
137
138
139
140
141
142
143
144
145
146
147
148
149
150
151
152
153
154
155
156
157
158
159
160
161
162
163
164
165
166
167
168
169
170
171
172
173
174
175
176
177
178
179
180
181
182
183
184
185
186
187
188
189
190
191
192
/*
 * Copyright (C) 2008, Morgan Quigley and Willow Garage, Inc.
 *
 * Redistribution and use in source and binary forms, with or without
 * modification, are permitted provided that the following conditions are met:
 *   * Redistributions of source code must retain the above copyright notice,
 *     this list of conditions and the following disclaimer.
 *   * Redistributions in binary form must reproduce the above copyright
 *     notice, this list of conditions and the following disclaimer in the
 *     documentation and/or other materials provided with the distribution.
 *   * Neither the names of Stanford University or Willow Garage, Inc. nor the names of its
 *     contributors may be used to endorse or promote products derived from
 *     this software without specific prior written permission.
 *
 * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
 * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
 * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
 * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
 * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
 * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
 * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
 * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
 * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
 * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
 * POSSIBILITY OF SUCH DAMAGE.
 */

#ifndef ROSCPP_PUBLICATION_H
#define ROSCPP_PUBLICATION_H

#include "ros/forwards.h"
#include "ros/advertise_options.h"
#include "common.h"
#include "xmlrpcpp/XmlRpc.h"

#include <boost/thread/mutex.hpp>

#include <boost/shared_ptr.hpp>
#include <boost/shared_array.hpp>

#include <vector>

namespace ros
{

class SubscriberLink;
typedef boost::shared_ptr<SubscriberLink> SubscriberLinkPtr;
typedef std::vector<SubscriberLinkPtr> V_SubscriberLink;

/**
 * \brief A Publication manages an advertised topic
 */
class ROSCPP_DECL Publication
{
public:
  Publication(const std::string &name,
            const std::string& datatype,
            const std::string& _md5sum,
            const std::string& message_definition,
            size_t max_queue,
            bool latch,
            bool has_header);

  ~Publication();

  void addCallbacks(const SubscriberCallbacksPtr& callbacks);
  void removeCallbacks(const SubscriberCallbacksPtr& callbacks);

  /**
   * \brief queues an outgoing message into each of the publishers, so that it gets sent to every subscriber
   */
  bool enqueueMessage(const SerializedMessage& m);
  /**
   * \brief returns the max queue size of this publication
   */
  inline size_t getMaxQueue() { return max_queue_; }
  /**
   * \brief Get the accumulated stats for this publication
   */
  XmlRpc::XmlRpcValue getStats();
  /**
   * \brief Get the accumulated info for this publication
   */
  void getInfo(XmlRpc::XmlRpcValue& info);

  /**
   * \brief Returns whether or not this publication has any subscribers
   */
  bool hasSubscribers();
  /**
   * \brief Returns the number of subscribers this publication has
   */
  uint32_t getNumSubscribers();

  void getPublishTypes(bool& serialize, bool& nocopy, const std::type_info& ti);

  /**
   * \brief Returns the name of the topic this publication broadcasts to
   */
  const std::string& getName() const { return name_; }
  /**
   * \brief Returns the data type of the message published by this publication
   */
  const std::string& getDataType() const { return datatype_; }
  /**
   * \brief Returns the md5sum of the message published by this publication
   */
  const std::string& getMD5Sum() const { return md5sum_; }
  /**
   * \brief Returns the full definition of the message published by this publication
   */
  const std::string& getMessageDefinition() const { return message_definition_; }
  /**
   * \brief Returns the sequence number
   */
  uint32_t getSequence() { return seq_; }

  bool isLatched() { return latch_; }

  /**
   * \brief Adds a publisher to our list
   */
  void addSubscriberLink(const SubscriberLinkPtr& sub_link);
  /**
   * \brief Removes a publisher from our list (deleting it if it's the last reference)
   */
  void removeSubscriberLink(const SubscriberLinkPtr& sub_link);

  /**
   * \brief Drop this publication.  Disconnects all publishers.
   */
  void drop();
  /**
   * \brief Returns if this publication is valid or not
   */
  bool isDropped() { return dropped_; }

  uint32_t incrementSequence();

  size_t getNumCallbacks();

  bool isLatching() { return latch_; }

  void publish(SerializedMessage& m);
  void processPublishQueue();

  bool validateHeader(const Header& h, std::string& error_msg);

private:
  void dropAllConnections();

  /**
   * \brief Called when a new peer has connected. Calls the connection callback
   */
  void peerConnect(const SubscriberLinkPtr& sub_link);
  /**
   * \brief Called when a peer has disconnected. Calls the disconnection callback
   */
  void peerDisconnect(const SubscriberLinkPtr& sub_link);

  std::string name_;
  std::string datatype_;
  std::string md5sum_;
  std::string message_definition_;
  size_t max_queue_;
  uint32_t seq_;
  boost::mutex seq_mutex_;

  typedef std::vector<SubscriberCallbacksPtr> V_Callback;
  V_Callback callbacks_;
  boost::mutex callbacks_mutex_;

  V_SubscriberLink subscriber_links_;
  // We use a recursive mutex here for the rare case that a publish call causes another one (like in the case of a rosconsole call)
  boost::mutex subscriber_links_mutex_;

  bool dropped_;

  bool latch_;
  bool has_header_;
  SerializedMessage last_message_;

  uint32_t intraprocess_subscriber_count_;

  typedef std::vector<SerializedMessage> V_SerializedMessage;
  V_SerializedMessage publish_queue_;
  boost::mutex publish_queue_mutex_;
};

}

#endif // ROSCPP_PUBLICATION_H