cloud_accum.h
Go to the documentation of this file.
1 /*
2  * Copyright (c) 2020, the mcl_3dl 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 MCL_3DL_CLOUD_ACCUM_H
31 #define MCL_3DL_CLOUD_ACCUM_H
32 
33 #include <functional>
34 #include <memory>
35 #include <string>
36 #include <vector>
37 
38 #include <sensor_msgs/PointCloud2.h>
39 
40 namespace mcl_3dl
41 {
43 {
44 public:
45  using Ptr = std::shared_ptr<CloudAccumulationLogicBase>;
46 
47  virtual void push(
48  const std::string& key,
49  const sensor_msgs::PointCloud2::ConstPtr& msg,
50  std::function<void()> process,
51  std::function<bool(const sensor_msgs::PointCloud2::ConstPtr&)> accumulate,
52  std::function<void()> clear) = 0;
53 
54  virtual void reset() = 0;
55 };
56 
58 {
59 public:
60  void push(
61  const std::string& key,
62  const sensor_msgs::PointCloud2::ConstPtr& msg,
63  std::function<void()> process,
64  std::function<bool(const sensor_msgs::PointCloud2::ConstPtr&)> accumulate,
65  std::function<void()> clear) final;
66 
67  inline void reset() final
68  {
69  }
70 };
71 
73 {
74 public:
76  const size_t accum,
77  const size_t accum_max)
78  : accum_(accum)
79  , accum_max_(accum_max)
80  , cnt_accum_(0)
81  {
82  }
83 
84  void push(
85  const std::string& key,
86  const sensor_msgs::PointCloud2::ConstPtr& msg,
87  std::function<void()> process,
88  std::function<bool(const sensor_msgs::PointCloud2::ConstPtr&)> accumulate,
89  std::function<void()> clear) final;
90 
91  void reset() final;
92 
93 private:
94  size_t accum_;
95  size_t accum_max_;
96  size_t cnt_accum_;
97  std::vector<std::string> keys_;
98 };
99 } // namespace mcl_3dl
100 
101 #endif // MCL_3DL_CLOUD_ACCUM_H
std::vector< std::string > keys_
Definition: cloud_accum.h:97
virtual void push(const std::string &key, const sensor_msgs::PointCloud2::ConstPtr &msg, std::function< void()> process, std::function< bool(const sensor_msgs::PointCloud2::ConstPtr &)> accumulate, std::function< void()> clear)=0
CloudAccumulationLogic(const size_t accum, const size_t accum_max)
Definition: cloud_accum.h:75
std::shared_ptr< CloudAccumulationLogicBase > Ptr
Definition: cloud_accum.h:45


mcl_3dl
Author(s): Atsushi Watanabe
autogenerated on Wed May 12 2021 02:16:29