35 #include <sensor_msgs/PointCloud2.h> 42 const std::string& key,
43 const sensor_msgs::PointCloud2::ConstPtr& msg,
44 std::function<
void()> process,
45 std::function<
bool(
const sensor_msgs::PointCloud2::ConstPtr&)> accumulate,
46 std::function<
void()> clear)
54 const std::string& key,
55 const sensor_msgs::PointCloud2::ConstPtr& msg,
56 std::function<
void()> process,
57 std::function<
bool(
const sensor_msgs::PointCloud2::ConstPtr&)> accumulate,
58 std::function<
void()> clear)
62 if (keys_.size() < accum_max_)
64 if (keys_.size() == 0 || keys_.front() != key)
68 if (keys_.size() == 0)
83 if (cnt_accum_ < accum_)
104 "Number of the accumulated cloud exceeds limit. " 105 "Sensor with frame_id of %s may have been stopped.",
106 keys_.front().c_str());
116 keys_.push_back(key);
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 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