21 #include "glog/logging.h"    26 std::unique_ptr<OutlierRemovingPointsProcessor>
    30   return common::make_unique<OutlierRemovingPointsProcessor>(
    31       dictionary->
GetDouble(
"voxel_size"), next);
    40   LOG(INFO) << 
"Marking hits...";
    44     std::unique_ptr<PointsBatch> points) {
    63       LOG(INFO) << 
"Counting rays...";
    68       LOG(INFO) << 
"Filtering outliers...";
    74           << 
"Voxel filtering and outlier removal must be configured to occur "    75              "after any stages that require multiple passes.";
    83   for (
size_t i = 0; i < batch.
points.size(); ++i) {
    93   for (
size_t i = 0; i < batch.
points.size(); ++i) {
    94     const Eigen::Vector3f delta = batch.
points[i] - batch.
origin;
    95     const float length = delta.norm();
    99       if (
voxels_.value(index).hits > 0) {
   100         ++
voxels_.mutable_value(index)->rays;
   107     std::unique_ptr<PointsBatch> batch) {
   108   constexpr 
double kMissPerHitLimit = 3;
   109   std::vector<int> to_remove;
   110   for (
size_t i = 0; i < batch->points.size(); ++i) {
   111     const auto voxel = 
voxels_.value(
voxels_.GetCellIndex(batch->points[i]));
   112     if (!(voxel.rays < kMissPerHitLimit * voxel.hits)) {
   113       to_remove.push_back(i);
 void RemovePoints(std::vector< int > to_remove, PointsBatch *batch)
virtual void Process(std::unique_ptr< PointsBatch > points_batch)=0
void ProcessInPhaseTwo(const PointsBatch &batch)
double GetDouble(const string &key)
OutlierRemovingPointsProcessor(double voxel_size, PointsProcessor *next)
virtual FlushResult Flush()=0
PointsProcessor *const next_
void Process(std::unique_ptr< PointsBatch > batch) override
mapping_3d::HybridGridBase< VoxelData > voxels_
void ProcessInPhaseThree(std::unique_ptr< PointsBatch > batch)
static std::unique_ptr< OutlierRemovingPointsProcessor > FromDictionary(common::LuaParameterDictionary *dictionary, PointsProcessor *next)
FlushResult Flush() override
void ProcessInPhaseOne(const PointsBatch &batch)
std::vector< Eigen::Vector3f > points