Go to the documentation of this file.00001 #include "cartographer/io/hybrid_grid_points_processor.h"
00002
00003 #include <memory>
00004 #include <string>
00005
00006 #include "Eigen/Core"
00007 #include "absl/memory/memory.h"
00008 #include "cartographer/io/file_writer.h"
00009 #include "cartographer/io/points_batch.h"
00010 #include "cartographer/io/points_processor.h"
00011 #include "cartographer/mapping/3d/hybrid_grid.h"
00012 #include "cartographer/mapping/3d/range_data_inserter_3d.h"
00013 #include "cartographer/sensor/range_data.h"
00014 #include "glog/logging.h"
00015
00016 namespace cartographer {
00017 namespace io {
00018
00019 HybridGridPointsProcessor::HybridGridPointsProcessor(
00020 const double voxel_size,
00021 const mapping::proto::RangeDataInserterOptions3D&
00022 range_data_inserter_options,
00023 std::unique_ptr<FileWriter> file_writer, PointsProcessor* const next)
00024 : next_(next),
00025 range_data_inserter_(range_data_inserter_options),
00026 hybrid_grid_(voxel_size),
00027 file_writer_(std::move(file_writer)) {}
00028
00029 std::unique_ptr<HybridGridPointsProcessor>
00030 HybridGridPointsProcessor::FromDictionary(
00031 const FileWriterFactory& file_writer_factory,
00032 common::LuaParameterDictionary* const dictionary,
00033 PointsProcessor* const next) {
00034 return absl::make_unique<HybridGridPointsProcessor>(
00035 dictionary->GetDouble("voxel_size"),
00036 mapping::CreateRangeDataInserterOptions3D(
00037 dictionary->GetDictionary("range_data_inserter").get()),
00038 file_writer_factory(dictionary->GetString("filename")), next);
00039 }
00040
00041 void HybridGridPointsProcessor::Process(std::unique_ptr<PointsBatch> batch) {
00042 range_data_inserter_.Insert({batch->origin, batch->points, {}},
00043 &hybrid_grid_);
00044 next_->Process(std::move(batch));
00045 }
00046
00047 PointsProcessor::FlushResult HybridGridPointsProcessor::Flush() {
00048 const mapping::proto::HybridGrid hybrid_grid_proto = hybrid_grid_.ToProto();
00049 std::string serialized;
00050 hybrid_grid_proto.SerializeToString(&serialized);
00051 file_writer_->Write(serialized.data(), serialized.size());
00052 CHECK(file_writer_->Close());
00053
00054 switch (next_->Flush()) {
00055 case FlushResult::kRestartStream:
00056 LOG(FATAL) << "Hybrid grid generation must be configured to occur after "
00057 "any stages that require multiple passes.";
00058
00059 case FlushResult::kFinished:
00060 return FlushResult::kFinished;
00061 }
00062 LOG(FATAL) << "Failed to receive FlushResult::kFinished";
00063
00064
00065 return FlushResult::kFinished;
00066 }
00067
00068 }
00069 }