Go to the documentation of this file.00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #ifndef CARTOGRAPHER_IO_XRAY_POINTS_PROCESSOR_H_
00018 #define CARTOGRAPHER_IO_XRAY_POINTS_PROCESSOR_H_
00019
00020 #include <map>
00021
00022 #include "Eigen/Core"
00023 #include "cartographer/common/lua_parameter_dictionary.h"
00024 #include "cartographer/io/file_writer.h"
00025 #include "cartographer/io/points_processor.h"
00026 #include "cartographer/mapping/3d/hybrid_grid.h"
00027 #include "cartographer/mapping/detect_floors.h"
00028 #include "cartographer/mapping/proto/trajectory.pb.h"
00029 #include "cartographer/transform/rigid_transform.h"
00030
00031 namespace cartographer {
00032 namespace io {
00033
00034
00035 class XRayPointsProcessor : public PointsProcessor {
00036 public:
00037 constexpr static const char* kConfigurationFileActionName =
00038 "write_xray_image";
00039 enum class DrawTrajectories { kNo, kYes };
00040 XRayPointsProcessor(
00041 double voxel_size, double saturation_factor,
00042 const transform::Rigid3f& transform,
00043 const std::vector<mapping::Floor>& floors,
00044 const DrawTrajectories& draw_trajectories,
00045 const std::string& output_filename,
00046 const std::vector<mapping::proto::Trajectory>& trajectories,
00047 FileWriterFactory file_writer_factory, PointsProcessor* next);
00048
00049 static std::unique_ptr<XRayPointsProcessor> FromDictionary(
00050 const std::vector<mapping::proto::Trajectory>& trajectories,
00051 FileWriterFactory file_writer_factory,
00052 common::LuaParameterDictionary* dictionary, PointsProcessor* next);
00053
00054 ~XRayPointsProcessor() override {}
00055
00056 void Process(std::unique_ptr<PointsBatch> batch) override;
00057 FlushResult Flush() override;
00058
00059 Eigen::AlignedBox3i bounding_box() const { return bounding_box_; }
00060
00061 private:
00062 struct ColumnData {
00063 float sum_r = 0.;
00064 float sum_g = 0.;
00065 float sum_b = 0.;
00066 uint32_t count = 0;
00067 };
00068
00069 struct Aggregation {
00070 mapping::HybridGridBase<bool> voxels;
00071 std::map<std::pair<int, int>, ColumnData> column_data;
00072 };
00073
00074 void WriteVoxels(const Aggregation& aggregation,
00075 FileWriter* const file_writer);
00076 void Insert(const PointsBatch& batch, Aggregation* aggregation);
00077
00078 const DrawTrajectories draw_trajectories_;
00079 const std::vector<mapping::proto::Trajectory> trajectories_;
00080 FileWriterFactory file_writer_factory_;
00081 PointsProcessor* const next_;
00082
00083
00084 std::vector<mapping::Floor> floors_;
00085
00086 const std::string output_filename_;
00087 const transform::Rigid3f transform_;
00088
00089
00090 std::vector<Aggregation> aggregations_;
00091
00092
00093 Eigen::AlignedBox3i bounding_box_;
00094
00095
00096
00097 const double saturation_factor_;
00098 };
00099
00100 }
00101 }
00102
00103 #endif // CARTOGRAPHER_IO_XRAY_POINTS_PROCESSOR_H_