This file is indexed.

/usr/include/message_filters/time_sequencer.h is in libmessage-filters-dev 1.13.5+ds1-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
193
194
195
196
197
198
199
200
201
202
203
204
205
206
207
208
209
210
211
212
213
214
215
216
217
218
219
220
221
222
223
224
225
226
227
228
229
230
231
232
233
234
235
236
237
238
239
240
241
242
243
/*********************************************************************
* Software License Agreement (BSD License)
*
*  Copyright (c) 2008, Willow Garage, Inc.
*  All rights reserved.
*
*  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 name of the Willow Garage 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 MESSAGE_FILTERS_TIME_SEQUENCER_H
#define MESSAGE_FILTERS_TIME_SEQUENCER_H

#include <ros/ros.h>

#include "connection.h"
#include "simple_filter.h"

namespace message_filters
{

/**
 * \class TimeSequencer
 *
 * \brief Sequences messages based on the timestamp of their header.
 *
 * The TimeSequencer object is templated on the type of message being sequenced.
 *
 * \section behavior BEHAVIOR

 * At construction, the TimeSequencer takes a ros::Duration
 * "delay" which specifies how long to queue up messages to
 * provide a time sequencing over them.  As messages arrive they are
 * sorted according to their time stamps.  A callback for a message is
 * never invoked until the messages' time stamp is out of date by at
 * least delay.  However, for all messages which are out of date
 * by at least delay, their callback are invoked and guaranteed
 * to be in temporal order.  If a message arrives from a time \b prior
 * to a message which has already had its callback invoked, it is
 * thrown away.
 *
 * \section connections CONNECTIONS
 *
 * TimeSequencer's input and output connections are both of the same signature as roscpp subscription callbacks, ie.
\verbatim
void callback(const boost::shared_ptr<M const>&);
\endverbatim
 *
 */
template<class M>
class TimeSequencer : public SimpleFilter<M>
{
public:
  typedef boost::shared_ptr<M const> MConstPtr;
  typedef ros::MessageEvent<M const> EventType;

  /**
   * \brief Constructor
   * \param f A filter to connect this sequencer's input to
   * \param delay The minimum time to hold a message before passing it through.
   * \param update_rate The rate at which to check for messages which have passed "delay"
   * \param queue_size The number of messages to store
   * \param nh (optional) The NodeHandle to use to create the ros::Timer that runs at update_rate
   */
  template<class F>
  TimeSequencer(F& f, ros::Duration delay, ros::Duration update_rate, uint32_t queue_size, ros::NodeHandle nh = ros::NodeHandle())
  : delay_(delay)
  , update_rate_(update_rate)
  , queue_size_(queue_size)
  , nh_(nh)
  {
    init();
    connectInput(f);
  }

  /**
   * \brief Constructor
   *
   * This version of the constructor does not take a filter immediately.  You can connect to a filter later with the connectInput() function
   *
   * \param delay The minimum time to hold a message before passing it through.
   * \param update_rate The rate at which to check for messages which have passed "delay"
   * \param queue_size The number of messages to store
   * \param nh (optional) The NodeHandle to use to create the ros::Timer that runs at update_rate
   */
  TimeSequencer(ros::Duration delay, ros::Duration update_rate, uint32_t queue_size, ros::NodeHandle nh = ros::NodeHandle())
  : delay_(delay)
  , update_rate_(update_rate)
  , queue_size_(queue_size)
  , nh_(nh)
  {
    init();
  }

  /**
   * \brief Connect this filter's input to another filter's output.
   */
  template<class F>
  void connectInput(F& f)
  {
    incoming_connection_.disconnect();
    incoming_connection_ = f.registerCallback(typename SimpleFilter<M>::EventCallback(boost::bind(&TimeSequencer::cb, this, _1)));
  }

  ~TimeSequencer()
  {
    update_timer_.stop();
    incoming_connection_.disconnect();
  }

  void add(const EventType& evt)
  {
    namespace mt = ros::message_traits;

    boost::mutex::scoped_lock lock(messages_mutex_);
    if (mt::TimeStamp<M>::value(*evt.getMessage()) < last_time_)
    {
      return;
    }

    messages_.insert(evt);

    if (queue_size_ != 0 && messages_.size() > queue_size_)
    {
      messages_.erase(*messages_.begin());
    }
  }

  /**
   * \brief Manually add a message to the cache.
   */
  void add(const MConstPtr& msg)
  {
    EventType evt(msg);
    add(evt);
  }

private:
  class MessageSort
  {
  public:
    bool operator()(const EventType& lhs, const EventType& rhs) const
    {
      namespace mt = ros::message_traits;
      return mt::TimeStamp<M>::value(*lhs.getMessage()) < mt::TimeStamp<M>::value(*rhs.getMessage());
    }
  };
  typedef std::multiset<EventType, MessageSort> S_Message;
  typedef std::vector<EventType> V_Message;

  void cb(const EventType& evt)
  {
    add(evt);
  }

  void dispatch()
  {
    namespace mt = ros::message_traits;

    V_Message to_call;

    {
      boost::mutex::scoped_lock lock(messages_mutex_);

      while (!messages_.empty())
      {
        const EventType& e = *messages_.begin();
        ros::Time stamp = mt::TimeStamp<M>::value(*e.getMessage());
        if (stamp + delay_ <= ros::Time::now())
        {
          last_time_ = stamp;
          to_call.push_back(e);
          messages_.erase(messages_.begin());
        }
        else
        {
          break;
        }
      }
    }

    {
      typename V_Message::iterator it = to_call.begin();
      typename V_Message::iterator end = to_call.end();
      for (; it != end; ++it)
      {
        this->signalMessage(*it);
      }
    }
  }

  void update(const ros::TimerEvent&)
  {
    dispatch();
  }

  void init()
  {
    update_timer_ = nh_.createTimer(update_rate_, &TimeSequencer::update, this);
  }

  ros::Duration delay_;
  ros::Duration update_rate_;
  uint32_t queue_size_;
  ros::NodeHandle nh_;

  ros::Timer update_timer_;

  Connection incoming_connection_;


  S_Message messages_;
  boost::mutex messages_mutex_;
  ros::Time last_time_;
};

}

#endif