outlier_removing_points_processor.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #include "cartographer/io/outlier_removing_points_processor.h"
00018 
00019 #include "absl/memory/memory.h"
00020 #include "cartographer/common/lua_parameter_dictionary.h"
00021 #include "glog/logging.h"
00022 
00023 namespace cartographer {
00024 namespace io {
00025 
00026 std::unique_ptr<OutlierRemovingPointsProcessor>
00027 OutlierRemovingPointsProcessor::FromDictionary(
00028     common::LuaParameterDictionary* const dictionary,
00029     PointsProcessor* const next) {
00030   const double miss_per_hit_limit = [&]() {
00031     if (!dictionary->HasKey("miss_per_hit_limit")) {
00032       LOG(INFO) << "Using default value of 3 for miss_per_hit_limit.";
00033       return 3.;
00034     } else {
00035       return dictionary->GetDouble("miss_per_hit_limit");
00036     }
00037   }();
00038   return absl::make_unique<OutlierRemovingPointsProcessor>(
00039       dictionary->GetDouble("voxel_size"), miss_per_hit_limit, next);
00040 }
00041 
00042 OutlierRemovingPointsProcessor::OutlierRemovingPointsProcessor(
00043     const double voxel_size, const double miss_per_hit_limit,
00044     PointsProcessor* next)
00045     : voxel_size_(voxel_size),
00046       miss_per_hit_limit_(miss_per_hit_limit),
00047       next_(next),
00048       state_(State::kPhase1),
00049       voxels_(voxel_size_) {
00050   LOG(INFO) << "Marking hits...";
00051 }
00052 
00053 void OutlierRemovingPointsProcessor::Process(
00054     std::unique_ptr<PointsBatch> batch) {
00055   switch (state_) {
00056     case State::kPhase1:
00057       ProcessInPhaseOne(*batch);
00058       break;
00059 
00060     case State::kPhase2:
00061       ProcessInPhaseTwo(*batch);
00062       break;
00063 
00064     case State::kPhase3:
00065       ProcessInPhaseThree(std::move(batch));
00066       break;
00067   }
00068 }
00069 
00070 PointsProcessor::FlushResult OutlierRemovingPointsProcessor::Flush() {
00071   switch (state_) {
00072     case State::kPhase1:
00073       LOG(INFO) << "Counting rays...";
00074       state_ = State::kPhase2;
00075       return FlushResult::kRestartStream;
00076 
00077     case State::kPhase2:
00078       LOG(INFO) << "Filtering outliers...";
00079       state_ = State::kPhase3;
00080       return FlushResult::kRestartStream;
00081 
00082     case State::kPhase3:
00083       CHECK(next_->Flush() == FlushResult::kFinished)
00084           << "Voxel filtering and outlier removal must be configured to occur "
00085              "after any stages that require multiple passes.";
00086       return FlushResult::kFinished;
00087   }
00088   LOG(FATAL);
00089 }
00090 
00091 void OutlierRemovingPointsProcessor::ProcessInPhaseOne(
00092     const PointsBatch& batch) {
00093   for (size_t i = 0; i < batch.points.size(); ++i) {
00094     ++voxels_.mutable_value(voxels_.GetCellIndex(batch.points[i].position))
00095           ->hits;
00096   }
00097 }
00098 
00099 void OutlierRemovingPointsProcessor::ProcessInPhaseTwo(
00100     const PointsBatch& batch) {
00101   // TODO(whess): This samples every 'voxel_size' distance and could be improved
00102   // by better ray casting, and also by marking the hits of the current range
00103   // data to be excluded.
00104   for (size_t i = 0; i < batch.points.size(); ++i) {
00105     const Eigen::Vector3f delta = batch.points[i].position - batch.origin;
00106     const float length = delta.norm();
00107     for (float x = 0; x < length; x += voxel_size_) {
00108       const Eigen::Array3i index =
00109           voxels_.GetCellIndex(batch.origin + (x / length) * delta);
00110       if (voxels_.value(index).hits > 0) {
00111         ++voxels_.mutable_value(index)->rays;
00112       }
00113     }
00114   }
00115 }
00116 
00117 void OutlierRemovingPointsProcessor::ProcessInPhaseThree(
00118     std::unique_ptr<PointsBatch> batch) {
00119   absl::flat_hash_set<int> to_remove;
00120   for (size_t i = 0; i < batch->points.size(); ++i) {
00121     const VoxelData voxel =
00122         voxels_.value(voxels_.GetCellIndex(batch->points[i].position));
00123     if (!(voxel.rays < miss_per_hit_limit_ * voxel.hits)) {
00124       to_remove.insert(i);
00125     }
00126   }
00127   RemovePoints(to_remove, batch.get());
00128   next_->Process(std::move(batch));
00129 }
00130 
00131 }  // namespace io
00132 }  // namespace cartographer


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:35