This file is indexed.

/usr/include/laser_geometry/laser_geometry.h is in liblaser-geometry-dev 1.6.4-2.

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
344
345
346
347
348
349
350
351
352
353
354
/*
 * 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, 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 LASER_SCAN_UTILS_LASERSCAN_H
#define LASER_SCAN_UTILS_LASERSCAN_H

#include <map>
#include <iostream>
#include <sstream>

#include "boost/numeric/ublas/matrix.hpp"
#include "boost/thread/mutex.hpp"

#include <tf/tf.h>
#include <tf2/buffer_core.h>

#include "sensor_msgs/LaserScan.h"
#include "sensor_msgs/PointCloud.h"
#include "sensor_msgs/PointCloud.h"

#include <Eigen/Core>
#include <sensor_msgs/PointCloud2.h>

namespace laser_geometry
{
  // NOTE: invalid scan errors (will be present in LaserScan.msg in D-Turtle)
  const float LASER_SCAN_INVALID   = -1.0;
  const float LASER_SCAN_MIN_RANGE = -2.0;
  const float LASER_SCAN_MAX_RANGE = -3.0;

  namespace channel_option
  {
  //! Enumerated output channels options.
  /*!
   * An OR'd set of these options is passed as the final argument of
   * the projectLaser and transformLaserScanToPointCloud calls to
   * enable generation of the appropriate set of additional channels.
   */
    enum ChannelOption
      {
        None = 0x00,      //!< Enable no channels
        Intensity = 0x01, //!< Enable "intensities" channel
        Index     = 0x02, //!< Enable "index" channel
        Distance  = 0x04, //!< Enable "distances" channel
        Timestamp = 0x08, //!< Enable "stamps" channel
        Viewpoint = 0x10, //!< Enable "viewpoint" channel
        Default   = (Intensity | Index) //!< Enable "intensities" and "index" channels
      };
  }

  //! \brief A Class to Project Laser Scan
  /*!
   * This class will project laser scans into point clouds.  It caches
   * unit vectors between runs (provided the angular resolution of
   * your scanner is not changing) to avoid excess computation.
   *
   * By default all range values less than the scanner min_range, and
   * greater than the scanner max_range are removed from the generated
   * point cloud, as these are assumed to be invalid.
   *
   * If it is important to preserve a mapping between the index of
   * range values and points in the cloud, the recommended approach is
   * to pre-filter your laser_scan message to meet the requiremnt that all
   * ranges are between min and max_range.
   *
   * The generated PointClouds have a number of channels which can be enabled
   * through the use of ChannelOption.
   * - channel_option::Intensity - Create a channel named "intensities" with the intensity of the return for each point
   * - channel_option::Index - Create a channel named "index" containing the index from the original array for each point
   * - channel_option::Distance - Create a channel named "distances" containing the distance from the laser to each point
   * - channel_option::Timestamp - Create a channel named "stamps" containing the specific timestamp at which each point was measured
   */
  class LaserProjection
    {

    public:

      LaserProjection() : angle_min_(0), angle_max_(0) {}

      //! Destructor to deallocate stored unit vectors
      ~LaserProjection();

      //! Project a sensor_msgs::LaserScan into a sensor_msgs::PointCloud
      /*!
       * Project a single laser scan from a linear array into a 3D
       * point cloud.  The generated cloud will be in the same frame
       * as the original laser scan.
       *
       * \param scan_in The input laser scan
       * \param cloud_out The output point cloud
       * \param range_cutoff An additional range cutoff which can be
       *   applied to discard everything above it.
       *   Defaults to -1.0, which means the laser scan max range.
       * \param channel_option An OR'd set of channels to include.
       *   Options include: channel_option::Default,
       *   channel_option::Intensity, channel_option::Index,
       *   channel_option::Distance, channel_option::Timestamp.
       */
      void projectLaser (const sensor_msgs::LaserScan& scan_in,
                         sensor_msgs::PointCloud& cloud_out,
                         double range_cutoff = -1.0,
                         int channel_options = channel_option::Default)
      {
        return projectLaser_ (scan_in, cloud_out, range_cutoff, false, channel_options);
      }

      //! Project a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2
      /*!
       * Project a single laser scan from a linear array into a 3D
       * point cloud.  The generated cloud will be in the same frame
       * as the original laser scan.
       *
       * \param scan_in The input laser scan
       * \param cloud_out The output point cloud
       * \param range_cutoff An additional range cutoff which can be
       *   applied to discard everything above it.
       *   Defaults to -1.0, which means the laser scan max range.
       * \param channel_option An OR'd set of channels to include.
       *   Options include: channel_option::Default,
       *   channel_option::Intensity, channel_option::Index,
       *   channel_option::Distance, channel_option::Timestamp.
       */
      void projectLaser (const sensor_msgs::LaserScan& scan_in,
                         sensor_msgs::PointCloud2 &cloud_out,
                         double range_cutoff = -1.0,
                         int channel_options = channel_option::Default)
      {
        projectLaser_(scan_in, cloud_out, range_cutoff, channel_options);
      }


      //! Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud in target frame
      /*!
       * Transform a single laser scan from a linear array into a 3D
       * point cloud, accounting for movement of the laser over the
       * course of the scan.  In order for this transform to be
       * meaningful at a single point in time, the target_frame must
       * be a fixed reference frame.  See the tf documentation for
       * more information on fixed frames.
       *
       * \param target_frame The frame of the resulting point cloud
       * \param scan_in The input laser scan
       * \param cloud_out The output point cloud
       * \param tf a tf::Transformer object to use to perform the
       *   transform
       * \param range_cutoff An additional range cutoff which can be
       *   applied to discard everything above it.
       * \param channel_option An OR'd set of channels to include.
       *   Options include: channel_option::Default,
       *   channel_option::Intensity, channel_option::Index,
       *   channel_option::Distance, channel_option::Timestamp.
       */
      void transformLaserScanToPointCloud (const std::string& target_frame,
                                           const sensor_msgs::LaserScan& scan_in,
                                           sensor_msgs::PointCloud& cloud_out,
                                           tf::Transformer& tf,
                                           double range_cutoff,
                                           int channel_options = channel_option::Default)
      {
        return transformLaserScanToPointCloud_ (target_frame, cloud_out, scan_in, tf, range_cutoff, channel_options);
      }

      //! Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud in target frame
      /*!
       * Transform a single laser scan from a linear array into a 3D
       * point cloud, accounting for movement of the laser over the
       * course of the scan.  In order for this transform to be
       * meaningful at a single point in time, the target_frame must
       * be a fixed reference frame.  See the tf documentation for
       * more information on fixed frames.
       *
       * \param target_frame The frame of the resulting point cloud
       * \param scan_in The input laser scan
       * \param cloud_out The output point cloud
       * \param tf a tf::Transformer object to use to perform the
       *   transform
       * \param channel_option An OR'd set of channels to include.
       *   Options include: channel_option::Default,
       *   channel_option::Intensity, channel_option::Index,
       *   channel_option::Distance, channel_option::Timestamp.
       */
      void transformLaserScanToPointCloud (const std::string& target_frame,
                                           const sensor_msgs::LaserScan& scan_in,
                                           sensor_msgs::PointCloud& cloud_out,
                                           tf::Transformer& tf,
                                           int channel_options = channel_option::Default)
      {
        return transformLaserScanToPointCloud_ (target_frame, cloud_out, scan_in, tf, -1.0, channel_options);
      }

      //! Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2 in target frame
      /*!
       * Transform a single laser scan from a linear array into a 3D
       * point cloud, accounting for movement of the laser over the
       * course of the scan.  In order for this transform to be
       * meaningful at a single point in time, the target_frame must
       * be a fixed reference frame.  See the tf documentation for
       * more information on fixed frames.
       *
       * \param target_frame The frame of the resulting point cloud
       * \param scan_in The input laser scan
       * \param cloud_out The output point cloud
       * \param tf a tf::Transformer object to use to perform the
       *   transform
       * \param range_cutoff An additional range cutoff which can be
       *   applied to discard everything above it.
       *   Defaults to -1.0, which means the laser scan max range.
       * \param channel_option An OR'd set of channels to include.
       *   Options include: channel_option::Default,
       *   channel_option::Intensity, channel_option::Index,
       *   channel_option::Distance, channel_option::Timestamp.
       */
      void transformLaserScanToPointCloud(const std::string &target_frame,
                                           const sensor_msgs::LaserScan &scan_in,
                                           sensor_msgs::PointCloud2 &cloud_out,
                                           tf::Transformer &tf,
                                           double range_cutoff = -1.0,
                                           int channel_options = channel_option::Default)
      {
        transformLaserScanToPointCloud_(target_frame, scan_in, cloud_out, tf, range_cutoff, channel_options);
      }

      //! Transform a sensor_msgs::LaserScan into a sensor_msgs::PointCloud2 in target frame
      /*!
       * Transform a single laser scan from a linear array into a 3D
       * point cloud, accounting for movement of the laser over the
       * course of the scan.  In order for this transform to be
       * meaningful at a single point in time, the target_frame must
       * be a fixed reference frame.  See the tf documentation for
       * more information on fixed frames.
       *
       * \param target_frame The frame of the resulting point cloud
       * \param scan_in The input laser scan
       * \param cloud_out The output point cloud
       * \param tf a tf2::BufferCore object to use to perform the
       *   transform
       * \param range_cutoff An additional range cutoff which can be
       *   applied to discard everything above it.
       *   Defaults to -1.0, which means the laser scan max range.
       * \param channel_option An OR'd set of channels to include.
       *   Options include: channel_option::Default,
       *   channel_option::Intensity, channel_option::Index,
       *   channel_option::Distance, channel_option::Timestamp.
       */
      void transformLaserScanToPointCloud(const std::string &target_frame,
                                          const sensor_msgs::LaserScan &scan_in,
                                          sensor_msgs::PointCloud2 &cloud_out,
                                          tf2::BufferCore &tf,
                                          double range_cutoff = -1.0,
                                          int channel_options = channel_option::Default)
      {
        transformLaserScanToPointCloud_(target_frame, scan_in, cloud_out, tf, range_cutoff, channel_options);
      }

    protected:

      //! Internal protected representation of getUnitVectors
      /*!
       * This function should not be used by external users, however,
       * it is left protected so that test code can evaluate it
       * appropriately.
       */
      const boost::numeric::ublas::matrix<double>& getUnitVectors_(double angle_min,
                                                                   double angle_max,
                                                                   double angle_increment,
                                                                   unsigned int length);

    private:

      //! Internal hidden representation of projectLaser
      void projectLaser_ (const sensor_msgs::LaserScan& scan_in,
                          sensor_msgs::PointCloud& cloud_out,
                          double range_cutoff,
                          bool preservative,
                          int channel_options);

      //! Internal hidden representation of projectLaser
      void projectLaser_ (const sensor_msgs::LaserScan& scan_in,
                          sensor_msgs::PointCloud2 &cloud_out,
                          double range_cutoff,
                          int channel_options);

      //! Internal hidden representation of transformLaserScanToPointCloud
      void transformLaserScanToPointCloud_ (const std::string& target_frame,
                                            sensor_msgs::PointCloud& cloud_out,
                                            const sensor_msgs::LaserScan& scan_in,
                                            tf::Transformer & tf,
                                            double range_cutoff,
                                            int channel_options);

      //! Internal hidden representation of transformLaserScanToPointCloud2
      void transformLaserScanToPointCloud_ (const std::string &target_frame,
                                            const sensor_msgs::LaserScan &scan_in,
                                            sensor_msgs::PointCloud2 &cloud_out,
                                            tf::Transformer &tf,
                                            double range_cutoff,
                                            int channel_options);

      //! Internal hidden representation of transformLaserScanToPointCloud2
      void transformLaserScanToPointCloud_ (const std::string &target_frame,
                                            const sensor_msgs::LaserScan &scan_in,
                                            sensor_msgs::PointCloud2 &cloud_out,
                                            tf2::BufferCore &tf,
                                            double range_cutoff,
                                            int channel_options);

      //! Function used by the several forms of transformLaserScanToPointCloud_
      void transformLaserScanToPointCloud_ (const std::string &target_frame,
                                            const sensor_msgs::LaserScan &scan_in,
                                            sensor_msgs::PointCloud2 &cloud_out,
                                            tf2::Quaternion quat_start,
                                            tf2::Vector3 origin_start,
                                            tf2::Quaternion quat_end,
                                            tf2::Vector3 origin_end,
                                            double range_cutoff,
                                            int channel_options);

      //! Internal map of pointers to stored values
      std::map<std::string,boost::numeric::ublas::matrix<double>* > unit_vector_map_;
      float angle_min_;
      float angle_max_;
      Eigen::ArrayXXd co_sine_map_;
      boost::mutex guv_mutex_;
    };

}

#endif //LASER_SCAN_UTILS_LASERSCAN_H