pointcloud_accumulator.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2014-2017, the neonavigation authors
3  * All rights reserved.
4  *
5  * Redistribution and use in source and binary forms, with or without
6  * modification, are permitted provided that the following conditions are met:
7  *
8  * * Redistributions of source code must retain the above copyright
9  * notice, this list of conditions and the following disclaimer.
10  * * Redistributions in binary form must reproduce the above copyright
11  * notice, this list of conditions and the following disclaimer in the
12  * documentation and/or other materials provided with the distribution.
13  * * Neither the name of the copyright holder nor the names of its
14  * contributors may be used to endorse or promote products derived from
15  * this software without specific prior written permission.
16  *
17  * THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
18  * AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
19  * IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE
20  * ARE DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT OWNER OR CONTRIBUTORS BE
21  * LIABLE FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR
22  * CONSEQUENTIAL DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF
23  * SUBSTITUTE GOODS OR SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS
24  * INTERRUPTION) HOWEVER CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN
25  * CONTRACT, STRICT LIABILITY, OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE)
26  * ARISING IN ANY WAY OUT OF THE USE OF THIS SOFTWARE, EVEN IF ADVISED OF THE
27  * POSSIBILITY OF SUCH DAMAGE.
28  */
29 
30 #ifndef COSTMAP_CSPACE_POINTCLOUD_ACCUMULATOR_H
31 #define COSTMAP_CSPACE_POINTCLOUD_ACCUMULATOR_H
32 
33 #include <ros/ros.h>
34 
35 #include <list>
36 
37 namespace costmap_cspace
38 {
39 template <typename T>
41 {
42 public:
43  class Points : public T
44  {
45  public:
47 
48  Points(const T& points, const ros::Time& stamp)
49  : T(points)
50  , stamp_(stamp)
51  {
52  }
53  };
54 
56  {
57  }
58 
59  explicit PointcloudAccumurator(const ros::Duration& duration)
60  {
61  reset(duration);
62  }
63 
64  void reset(const ros::Duration& duration)
65  {
66  time_to_hold_ = duration;
67  clear();
68  }
69 
70  void clear()
71  {
72  points_.clear();
73  }
74 
75  void push(const Points& points)
76  {
77  for (auto it = points_.begin(); it != points_.end(); ++it)
78  {
79  if (it->stamp_ + time_to_hold_ < points.stamp_)
80  {
81  it = points_.erase(it);
82  continue;
83  }
84  break;
85  }
86  points_.push_back(points);
87  }
88 
89  typename std::list<Points>::iterator begin()
90  {
91  return points_.begin();
92  }
93  typename std::list<Points>::iterator end()
94  {
95  return points_.end();
96  }
97 
98  typename std::list<Points>::const_iterator begin() const
99  {
100  return points_.cbegin();
101  }
102  typename std::list<Points>::const_iterator end() const
103  {
104  return points_.cend();
105  }
106 
107 protected:
109  std::list<Points> points_;
110 };
111 } // namespace costmap_cspace
112 
113 #endif // COSTMAP_CSPACE_POINTCLOUD_ACCUMULATOR_H
void reset(const ros::Duration &duration)
Points(const T &points, const ros::Time &stamp)
std::list< Points >::iterator begin()
std::list< Points >::const_iterator end() const
std::list< Points >::iterator end()
PointcloudAccumurator(const ros::Duration &duration)
std::list< Points >::const_iterator begin() const


costmap_cspace
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:20:29