30 #ifndef MCL_3DL_CLOUD_ACCUM_H 31 #define MCL_3DL_CLOUD_ACCUM_H 38 #include <sensor_msgs/PointCloud2.h> 45 using Ptr = std::shared_ptr<CloudAccumulationLogicBase>;
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;
54 virtual void reset() = 0;
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;
77 const size_t accum_max)
79 , accum_max_(accum_max)
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;
101 #endif // MCL_3DL_CLOUD_ACCUM_H
std::vector< std::string > keys_
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)
std::shared_ptr< CloudAccumulationLogicBase > Ptr