#include <cloud_accum.h>
|
| | CloudAccumulationLogic (const size_t accum, const size_t accum_max) |
| |
| 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) final |
| |
| void | reset () final |
| |
Definition at line 72 of file cloud_accum.h.
| mcl_3dl::CloudAccumulationLogic::CloudAccumulationLogic |
( |
const size_t |
accum, |
|
|
const size_t |
accum_max |
|
) |
| |
|
inline |
| void mcl_3dl::CloudAccumulationLogic::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 |
|
) |
| |
|
finalvirtual |
| void mcl_3dl::CloudAccumulationLogic::reset |
( |
| ) |
|
|
finalvirtual |
| size_t mcl_3dl::CloudAccumulationLogic::accum_ |
|
private |
| size_t mcl_3dl::CloudAccumulationLogic::accum_max_ |
|
private |
| size_t mcl_3dl::CloudAccumulationLogic::cnt_accum_ |
|
private |
| std::vector<std::string> mcl_3dl::CloudAccumulationLogic::keys_ |
|
private |
The documentation for this class was generated from the following files: