points_processor_pipeline_builder.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/points_processor_pipeline_builder.h"
00018 
00019 #include "absl/memory/memory.h"
00020 #include "cartographer/io/coloring_points_processor.h"
00021 #include "cartographer/io/counting_points_processor.h"
00022 #include "cartographer/io/fixed_ratio_sampling_points_processor.h"
00023 #include "cartographer/io/frame_id_filtering_points_processor.h"
00024 #include "cartographer/io/hybrid_grid_points_processor.h"
00025 #include "cartographer/io/intensity_to_color_points_processor.h"
00026 #include "cartographer/io/min_max_range_filtering_points_processor.h"
00027 #include "cartographer/io/null_points_processor.h"
00028 #include "cartographer/io/outlier_removing_points_processor.h"
00029 #include "cartographer/io/pcd_writing_points_processor.h"
00030 #include "cartographer/io/ply_writing_points_processor.h"
00031 #include "cartographer/io/probability_grid_points_processor.h"
00032 #include "cartographer/io/xray_points_processor.h"
00033 #include "cartographer/io/xyz_writing_points_processor.h"
00034 #include "cartographer/mapping/proto/trajectory.pb.h"
00035 
00036 namespace cartographer {
00037 namespace io {
00038 
00039 template <typename PointsProcessorType>
00040 void RegisterPlainPointsProcessor(
00041     PointsProcessorPipelineBuilder* const builder) {
00042   builder->Register(
00043       PointsProcessorType::kConfigurationFileActionName,
00044       [](common::LuaParameterDictionary* const dictionary,
00045          PointsProcessor* const next) -> std::unique_ptr<PointsProcessor> {
00046         return PointsProcessorType::FromDictionary(dictionary, next);
00047       });
00048 }
00049 
00050 template <typename PointsProcessorType>
00051 void RegisterFileWritingPointsProcessor(
00052     const FileWriterFactory& file_writer_factory,
00053     PointsProcessorPipelineBuilder* const builder) {
00054   builder->Register(
00055       PointsProcessorType::kConfigurationFileActionName,
00056       [file_writer_factory](
00057           common::LuaParameterDictionary* const dictionary,
00058           PointsProcessor* const next) -> std::unique_ptr<PointsProcessor> {
00059         return PointsProcessorType::FromDictionary(file_writer_factory,
00060                                                    dictionary, next);
00061       });
00062 }
00063 
00064 template <typename PointsProcessorType>
00065 void RegisterFileWritingPointsProcessorWithTrajectories(
00066     const std::vector<mapping::proto::Trajectory>& trajectories,
00067     const FileWriterFactory& file_writer_factory,
00068     PointsProcessorPipelineBuilder* const builder) {
00069   builder->Register(
00070       PointsProcessorType::kConfigurationFileActionName,
00071       [&trajectories, file_writer_factory](
00072           common::LuaParameterDictionary* const dictionary,
00073           PointsProcessor* const next) -> std::unique_ptr<PointsProcessor> {
00074         return PointsProcessorType::FromDictionary(
00075             trajectories, file_writer_factory, dictionary, next);
00076       });
00077 }
00078 
00079 void RegisterBuiltInPointsProcessors(
00080     const std::vector<mapping::proto::Trajectory>& trajectories,
00081     const FileWriterFactory& file_writer_factory,
00082     PointsProcessorPipelineBuilder* builder) {
00083   RegisterPlainPointsProcessor<CountingPointsProcessor>(builder);
00084   RegisterPlainPointsProcessor<FixedRatioSamplingPointsProcessor>(builder);
00085   RegisterPlainPointsProcessor<FrameIdFilteringPointsProcessor>(builder);
00086   RegisterPlainPointsProcessor<MinMaxRangeFiteringPointsProcessor>(builder);
00087   RegisterPlainPointsProcessor<OutlierRemovingPointsProcessor>(builder);
00088   RegisterPlainPointsProcessor<ColoringPointsProcessor>(builder);
00089   RegisterPlainPointsProcessor<IntensityToColorPointsProcessor>(builder);
00090   RegisterFileWritingPointsProcessor<PcdWritingPointsProcessor>(
00091       file_writer_factory, builder);
00092   RegisterFileWritingPointsProcessor<PlyWritingPointsProcessor>(
00093       file_writer_factory, builder);
00094   RegisterFileWritingPointsProcessor<XyzWriterPointsProcessor>(
00095       file_writer_factory, builder);
00096   RegisterFileWritingPointsProcessor<HybridGridPointsProcessor>(
00097       file_writer_factory, builder);
00098   RegisterFileWritingPointsProcessorWithTrajectories<XRayPointsProcessor>(
00099       trajectories, file_writer_factory, builder);
00100   RegisterFileWritingPointsProcessorWithTrajectories<
00101       ProbabilityGridPointsProcessor>(trajectories, file_writer_factory,
00102                                       builder);
00103 }
00104 
00105 void PointsProcessorPipelineBuilder::Register(const std::string& name,
00106                                               FactoryFunction factory) {
00107   CHECK(factories_.count(name) == 0) << "A points processor named '" << name
00108                                      << "' has already been registered.";
00109   factories_[name] = std::move(factory);
00110 }
00111 
00112 PointsProcessorPipelineBuilder::PointsProcessorPipelineBuilder() {}
00113 
00114 std::vector<std::unique_ptr<PointsProcessor>>
00115 PointsProcessorPipelineBuilder::CreatePipeline(
00116     common::LuaParameterDictionary* const dictionary) const {
00117   std::vector<std::unique_ptr<PointsProcessor>> pipeline;
00118   // The last consumer in the pipeline must exist, so that the one created after
00119   // it (and being before it in the pipeline) has a valid 'next' to point to.
00120   // The last consumer will just drop all points.
00121   pipeline.emplace_back(absl::make_unique<NullPointsProcessor>());
00122 
00123   std::vector<std::unique_ptr<common::LuaParameterDictionary>> configurations =
00124       dictionary->GetArrayValuesAsDictionaries();
00125 
00126   // We construct the pipeline starting at the back.
00127   for (auto it = configurations.rbegin(); it != configurations.rend(); it++) {
00128     const std::string action = (*it)->GetString("action");
00129     auto factory_it = factories_.find(action);
00130     CHECK(factory_it != factories_.end())
00131         << "Unknown action '" << action
00132         << "'. Did you register the correspoinding PointsProcessor?";
00133     pipeline.push_back(factory_it->second(it->get(), pipeline.back().get()));
00134   }
00135   return pipeline;
00136 }
00137 
00138 }  // namespace io
00139 }  // namespace cartographer


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