This file is indexed.

/usr/include/message_filters/cache.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
244
245
246
247
248
249
250
251
252
253
254
255
256
257
258
259
260
261
262
263
264
265
266
267
268
269
270
271
272
273
274
275
276
277
278
279
280
281
282
283
284
285
286
287
288
289
290
291
292
293
294
295
296
297
298
299
300
301
302
303
304
305
306
307
308
309
310
311
312
313
314
315
316
317
318
319
320
321
322
323
324
325
326
327
328
329
330
331
332
333
334
335
336
337
338
339
340
341
342
343
/*********************************************************************
* 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_CACHE_H_
#define MESSAGE_FILTERS_CACHE_H_

#include <deque>
#include "boost/thread.hpp"
#include "boost/shared_ptr.hpp"

#include "ros/time.h"

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

namespace message_filters
{

/**
 * \brief Stores a time history of messages
 *
 * Given a stream of messages, the most recent N messages are cached in a ring buffer,
 * from which time intervals of the cache can then be retrieved by the client.
 *
 * Cache immediately passes messages through to its output connections.
 *
 * \section connections CONNECTIONS
 *
 * Cache'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 Cache : public SimpleFilter<M>
{
public:
  typedef boost::shared_ptr<M const> MConstPtr;
  typedef ros::MessageEvent<M const> EventType;

  template<class F>
  Cache(F& f, unsigned int cache_size = 1)
  {
    setCacheSize(cache_size) ;
    connectInput(f) ;
  }

  /**
   * Initializes a Message Cache without specifying a parent filter. This implies that in
   * order to populate the cache, the user then has to call add themselves, or connectInput() is
   * called later
   */
  Cache(unsigned int cache_size = 1)
  {
    setCacheSize(cache_size);
  }

  template<class F>
  void connectInput(F& f)
  {
    incoming_connection_ = f.registerCallback(typename SimpleFilter<M>::EventCallback(boost::bind(&Cache::callback, this, _1)));
  }

  ~Cache()
  {
    incoming_connection_.disconnect();
  }

  /**
   * Set the size of the cache.
   * \param cache_size The new size the cache should be. Must be > 0
   */
  void setCacheSize(unsigned int cache_size)
  {
    if (cache_size == 0)
    {
      //ROS_ERROR("Cannot set max_size to 0") ;
      return ;
    }

    cache_size_ = cache_size ;
  }

  /**
   * \brief Add a message to the cache, and pop off any elements that are too old.
   * This method is registered with a data provider when connectTo is called.
   */
  void add(const MConstPtr& msg)
  {
    add(EventType(msg));
  }

  /**
   * \brief Add a message to the cache, and pop off any elements that are too old.
   * This method is registered with a data provider when connectTo is called.
   */
  void add(const EventType& evt)
  {
    namespace mt = ros::message_traits;

    //printf("  Cache Size: %u\n", cache_.size()) ;
    {
      boost::mutex::scoped_lock lock(cache_lock_);

      while (cache_.size() >= cache_size_)                       // Keep popping off old data until we have space for a new msg
        cache_.pop_front() ;                                     // The front of the deque has the oldest elem, so we can get rid of it

      // No longer naively pushing msgs to back. Want to make sure they're sorted correctly
      //cache_.push_back(msg) ;                                    // Add the newest message to the back of the deque

      typename std::deque<EventType >::reverse_iterator rev_it = cache_.rbegin();

      // Keep walking backwards along deque until we hit the beginning,
      //   or until we find a timestamp that's smaller than (or equal to) msg's timestamp
      ros::Time evt_stamp = mt::TimeStamp<M>::value(*evt.getMessage());
      while(rev_it != cache_.rend() && mt::TimeStamp<M>::value(*(*rev_it).getMessage()) > evt_stamp)
        rev_it++;

      // Add msg to the cache
      cache_.insert(rev_it.base(), evt);

    }

    this->signalMessage(evt);
  }

  /**
   * \brief Receive a vector of messages that occur between a start and end time (inclusive).
   *
   * This call is non-blocking, and only aggregates messages it has already received.
   * It will not wait for messages have not yet been received, but occur in the interval.
   * \param start The start of the requested interval
   * \param end The end of the requested interval
   */
  std::vector<MConstPtr> getInterval(const ros::Time& start, const ros::Time& end) const
  {
    namespace mt = ros::message_traits;

    boost::mutex::scoped_lock lock(cache_lock_);

    // Find the starting index. (Find the first index after [or at] the start of the interval)
    unsigned int start_index = 0 ;
    while(start_index < cache_.size() &&
          mt::TimeStamp<M>::value(*cache_[start_index].getMessage()) < start)
    {
      start_index++ ;
    }

    // Find the ending index. (Find the first index after the end of interval)
    unsigned int end_index = start_index ;
    while(end_index < cache_.size() &&
          mt::TimeStamp<M>::value(*cache_[end_index].getMessage()) <= end)
    {
      end_index++ ;
    }

    std::vector<MConstPtr> interval_elems ;
    interval_elems.reserve(end_index - start_index) ;
    for (unsigned int i=start_index; i<end_index; i++)
    {
      interval_elems.push_back(cache_[i].getMessage()) ;
    }

    return interval_elems ;
  }


  /**
   * \brief Retrieve the smallest interval of messages that surrounds an interval from start to end.
   *
   * If the messages in the cache do not surround (start,end), then this will return the interval
   * that gets closest to surrounding (start,end)
   */
  std::vector<MConstPtr> getSurroundingInterval(const ros::Time& start, const ros::Time& end) const
  {
    namespace mt = ros::message_traits;

    boost::mutex::scoped_lock lock(cache_lock_);
    // Find the starting index. (Find the first index after [or at] the start of the interval)
    unsigned int start_index = cache_.size()-1;
    while(start_index > 0 &&
          mt::TimeStamp<M>::value(*cache_[start_index].getMessage()) > start)
    {
      start_index--;
    }
    unsigned int end_index = start_index;
    while(end_index < cache_.size()-1 &&
          mt::TimeStamp<M>::value(*cache_[end_index].getMessage()) < end)
    {
      end_index++;
    }

    std::vector<MConstPtr> interval_elems;
    interval_elems.reserve(end_index - start_index + 1) ;
    for (unsigned int i=start_index; i<=end_index; i++)
    {
      interval_elems.push_back(cache_[i].getMessage()) ;
    }

    return interval_elems;
  }

  /**
   * \brief Grab the newest element that occurs right before the specified time.
   * \param time Time that must occur right after the returned elem
   * \returns shared_ptr to the newest elem that occurs before 'time'. NULL if doesn't exist
   */
  MConstPtr getElemBeforeTime(const ros::Time& time) const
  {
    namespace mt = ros::message_traits;

    boost::mutex::scoped_lock lock(cache_lock_);

    MConstPtr out ;

    unsigned int i=0 ;
    int elem_index = -1 ;
    while (i<cache_.size() &&
           mt::TimeStamp<M>::value(*cache_[i].getMessage()) < time)
    {
      elem_index = i ;
      i++ ;
    }

    if (elem_index >= 0)
      out = cache_[elem_index].getMessage() ;

    return out ;
  }

  /**
   * \brief Grab the oldest element that occurs right after the specified time.
   * \param time Time that must occur right before the returned elem
   * \returns shared_ptr to the oldest elem that occurs after 'time'. NULL if doesn't exist
   */
  MConstPtr getElemAfterTime(const ros::Time& time) const
  {
    namespace mt = ros::message_traits;

    boost::mutex::scoped_lock lock(cache_lock_);

    MConstPtr out ;

    int i=cache_.size()-1 ;
    int elem_index = -1 ;
    while (i>=0 &&
        mt::TimeStamp<M>::value(*cache_[i].getMessage()) > time)
    {
      elem_index = i ;
      i-- ;
    }

    if (elem_index >= 0)
      out = cache_[elem_index].getMessage() ;
    else
      out.reset() ;

    return out ;
  }

  /**
   * \brief Returns the timestamp associated with the newest packet cache
   */
  ros::Time getLatestTime() const
  {
    namespace mt = ros::message_traits;

    boost::mutex::scoped_lock lock(cache_lock_);

    ros::Time latest_time;

    if (cache_.size() > 0)
      latest_time = mt::TimeStamp<M>::value(*cache_.back().getMessage());

    return latest_time ;
  }

  /**
   * \brief Returns the timestamp associated with the oldest packet cache
   */
  ros::Time getOldestTime() const
  {
    namespace mt = ros::message_traits;

    boost::mutex::scoped_lock lock(cache_lock_);

    ros::Time oldest_time;

    if (cache_.size() > 0)
      oldest_time = mt::TimeStamp<M>::value(*cache_.front().getMessage());

    return oldest_time ;
  }


private:
  void callback(const EventType& evt)
  {
    add(evt);
  }

  mutable boost::mutex cache_lock_ ;            //!< Lock for cache_
  std::deque<EventType> cache_ ;        //!< Cache for the messages
  unsigned int cache_size_ ;            //!< Maximum number of elements allowed in the cache.

  Connection incoming_connection_;
};

}


#endif /* MESSAGE_FILTERS_CACHE_H_ */