00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include "cartographer/io/xray_points_processor.h"
00018
00019 #include <cmath>
00020 #include <string>
00021 #include <vector>
00022
00023 #include "Eigen/Core"
00024 #include "absl/memory/memory.h"
00025 #include "absl/strings/str_cat.h"
00026 #include "cartographer/common/lua_parameter_dictionary.h"
00027 #include "cartographer/common/math.h"
00028 #include "cartographer/io/draw_trajectories.h"
00029 #include "cartographer/io/image.h"
00030 #include "cartographer/mapping/3d/hybrid_grid.h"
00031 #include "cartographer/mapping/detect_floors.h"
00032 #include "cartographer/transform/transform.h"
00033
00034 namespace cartographer {
00035 namespace io {
00036 namespace {
00037
00038 struct PixelData {
00039 size_t num_occupied_cells_in_column = 0;
00040 float mean_r = 0.;
00041 float mean_g = 0.;
00042 float mean_b = 0.;
00043 };
00044
00045 class PixelDataMatrix {
00046 public:
00047 PixelDataMatrix(const int width, const int height)
00048 : width_(width), data_(width * height) {}
00049
00050 int width() const { return width_; }
00051 int height() const { return data_.size() / width_; }
00052 const PixelData& operator()(const int x, const int y) const {
00053 return data_.at(x + y * width_);
00054 }
00055
00056 PixelData& operator()(const int x, const int y) {
00057 return data_.at(x + y * width_);
00058 }
00059
00060 private:
00061 int width_;
00062 std::vector<PixelData> data_;
00063 };
00064
00065 float Mix(const float a, const float b, const float t) {
00066 return a * (1. - t) + t * b;
00067 }
00068
00069
00070 Image IntoImage(const PixelDataMatrix& matrix, double saturation_factor) {
00071 Image image(matrix.width(), matrix.height());
00072 float max = std::numeric_limits<float>::min();
00073 for (int y = 0; y < matrix.height(); ++y) {
00074 for (int x = 0; x < matrix.width(); ++x) {
00075 const PixelData& cell = matrix(x, y);
00076 if (cell.num_occupied_cells_in_column == 0.) {
00077 continue;
00078 }
00079 max = std::max<float>(max, std::log(cell.num_occupied_cells_in_column));
00080 }
00081 }
00082
00083 for (int y = 0; y < matrix.height(); ++y) {
00084 for (int x = 0; x < matrix.width(); ++x) {
00085 const PixelData& cell = matrix(x, y);
00086 if (cell.num_occupied_cells_in_column == 0.) {
00087 image.SetPixel(x, y, {{255, 255, 255}});
00088 continue;
00089 }
00090
00091
00092
00093
00094 const float saturation =
00095 std::min<float>(1.0, std::log(cell.num_occupied_cells_in_column) /
00096 max * saturation_factor);
00097 const FloatColor color = {{Mix(1.f, cell.mean_r, saturation),
00098 Mix(1.f, cell.mean_g, saturation),
00099 Mix(1.f, cell.mean_b, saturation)}};
00100 image.SetPixel(x, y, ToUint8Color(color));
00101 }
00102 }
00103 return image;
00104 }
00105
00106 bool ContainedIn(const common::Time& time,
00107 const std::vector<mapping::Timespan>& timespans) {
00108 for (const mapping::Timespan& timespan : timespans) {
00109 if (timespan.start <= time && time <= timespan.end) {
00110 return true;
00111 }
00112 }
00113 return false;
00114 }
00115
00116 }
00117
00118 XRayPointsProcessor::XRayPointsProcessor(
00119 const double voxel_size, const double saturation_factor,
00120 const transform::Rigid3f& transform,
00121 const std::vector<mapping::Floor>& floors,
00122 const DrawTrajectories& draw_trajectories,
00123 const std::string& output_filename,
00124 const std::vector<mapping::proto::Trajectory>& trajectories,
00125 FileWriterFactory file_writer_factory, PointsProcessor* const next)
00126 : draw_trajectories_(draw_trajectories),
00127 trajectories_(trajectories),
00128 file_writer_factory_(file_writer_factory),
00129 next_(next),
00130 floors_(floors),
00131 output_filename_(output_filename),
00132 transform_(transform),
00133 saturation_factor_(saturation_factor) {
00134 for (size_t i = 0; i < (floors_.empty() ? 1 : floors.size()); ++i) {
00135 aggregations_.emplace_back(
00136 Aggregation{mapping::HybridGridBase<bool>(voxel_size), {}});
00137 }
00138 }
00139
00140 std::unique_ptr<XRayPointsProcessor> XRayPointsProcessor::FromDictionary(
00141 const std::vector<mapping::proto::Trajectory>& trajectories,
00142 FileWriterFactory file_writer_factory,
00143 common::LuaParameterDictionary* const dictionary,
00144 PointsProcessor* const next) {
00145 std::vector<mapping::Floor> floors;
00146 const bool separate_floor = dictionary->HasKey("separate_floors") &&
00147 dictionary->GetBool("separate_floors");
00148 const auto draw_trajectories = (!dictionary->HasKey("draw_trajectories") ||
00149 dictionary->GetBool("draw_trajectories"))
00150 ? DrawTrajectories::kYes
00151 : DrawTrajectories::kNo;
00152 const double saturation_factor =
00153 dictionary->HasKey("saturation_factor")
00154 ? dictionary->GetDouble("saturation_factor")
00155 : 1.;
00156 if (separate_floor) {
00157 CHECK_EQ(trajectories.size(), 1)
00158 << "Can only detect floors with a single trajectory.";
00159 floors = mapping::DetectFloors(trajectories.at(0));
00160 }
00161
00162 return absl::make_unique<XRayPointsProcessor>(
00163 dictionary->GetDouble("voxel_size"), saturation_factor,
00164 transform::FromDictionary(dictionary->GetDictionary("transform").get())
00165 .cast<float>(),
00166 floors, draw_trajectories, dictionary->GetString("filename"),
00167 trajectories, file_writer_factory, next);
00168 }
00169
00170 void XRayPointsProcessor::WriteVoxels(const Aggregation& aggregation,
00171 FileWriter* const file_writer) {
00172 if (bounding_box_.isEmpty()) {
00173 LOG(WARNING) << "Not writing output: bounding box is empty.";
00174 return;
00175 }
00176
00177
00178 const auto voxel_index_to_pixel =
00179 [this](const Eigen::Array3i& index) -> Eigen::Array2i {
00180
00181 return Eigen::Array2i(bounding_box_.max()[1] - index[1],
00182 bounding_box_.max()[2] - index[2]);
00183 };
00184
00185
00186
00187 const int xsize = bounding_box_.sizes()[1] + 1;
00188 const int ysize = bounding_box_.sizes()[2] + 1;
00189 PixelDataMatrix pixel_data_matrix(xsize, ysize);
00190 for (mapping::HybridGridBase<bool>::Iterator it(aggregation.voxels);
00191 !it.Done(); it.Next()) {
00192 const Eigen::Array3i cell_index = it.GetCellIndex();
00193 const Eigen::Array2i pixel = voxel_index_to_pixel(cell_index);
00194 PixelData& pixel_data = pixel_data_matrix(pixel.x(), pixel.y());
00195 const auto& column_data = aggregation.column_data.at(
00196 std::make_pair(cell_index[1], cell_index[2]));
00197 pixel_data.mean_r = column_data.sum_r / column_data.count;
00198 pixel_data.mean_g = column_data.sum_g / column_data.count;
00199 pixel_data.mean_b = column_data.sum_b / column_data.count;
00200 ++pixel_data.num_occupied_cells_in_column;
00201 }
00202
00203 Image image = IntoImage(pixel_data_matrix, saturation_factor_);
00204 if (draw_trajectories_ == DrawTrajectories::kYes) {
00205 for (size_t i = 0; i < trajectories_.size(); ++i) {
00206 DrawTrajectory(
00207 trajectories_[i], GetColor(i),
00208 [&voxel_index_to_pixel, &aggregation,
00209 this](const transform::Rigid3d& pose) -> Eigen::Array2i {
00210 return voxel_index_to_pixel(aggregation.voxels.GetCellIndex(
00211 (transform_ * pose.cast<float>()).translation()));
00212 },
00213 image.GetCairoSurface().get());
00214 }
00215 }
00216
00217 image.WritePng(file_writer);
00218 CHECK(file_writer->Close());
00219 }
00220
00221 void XRayPointsProcessor::Insert(const PointsBatch& batch,
00222 Aggregation* const aggregation) {
00223 constexpr FloatColor kDefaultColor = {{0.f, 0.f, 0.f}};
00224 for (size_t i = 0; i < batch.points.size(); ++i) {
00225 const sensor::RangefinderPoint camera_point = transform_ * batch.points[i];
00226 const Eigen::Array3i cell_index =
00227 aggregation->voxels.GetCellIndex(camera_point.position);
00228 *aggregation->voxels.mutable_value(cell_index) = true;
00229 bounding_box_.extend(cell_index.matrix());
00230 ColumnData& column_data =
00231 aggregation->column_data[std::make_pair(cell_index[1], cell_index[2])];
00232 const auto& color =
00233 batch.colors.empty() ? kDefaultColor : batch.colors.at(i);
00234 column_data.sum_r += color[0];
00235 column_data.sum_g += color[1];
00236 column_data.sum_b += color[2];
00237 ++column_data.count;
00238 }
00239 }
00240
00241 void XRayPointsProcessor::Process(std::unique_ptr<PointsBatch> batch) {
00242 if (floors_.empty()) {
00243 CHECK_EQ(aggregations_.size(), 1);
00244 Insert(*batch, &aggregations_[0]);
00245 } else {
00246 for (size_t i = 0; i < floors_.size(); ++i) {
00247 if (!ContainedIn(batch->start_time, floors_[i].timespans)) {
00248 continue;
00249 }
00250 Insert(*batch, &aggregations_[i]);
00251 }
00252 }
00253 next_->Process(std::move(batch));
00254 }
00255
00256 PointsProcessor::FlushResult XRayPointsProcessor::Flush() {
00257 if (floors_.empty()) {
00258 CHECK_EQ(aggregations_.size(), 1);
00259 WriteVoxels(aggregations_[0],
00260 file_writer_factory_(output_filename_ + ".png").get());
00261 } else {
00262 for (size_t i = 0; i < floors_.size(); ++i) {
00263 WriteVoxels(
00264 aggregations_[i],
00265 file_writer_factory_(absl::StrCat(output_filename_, i, ".png"))
00266 .get());
00267 }
00268 }
00269
00270 switch (next_->Flush()) {
00271 case FlushResult::kRestartStream:
00272 LOG(FATAL) << "X-Ray generation must be configured to occur after any "
00273 "stages that require multiple passes.";
00274
00275 case FlushResult::kFinished:
00276 return FlushResult::kFinished;
00277 }
00278 LOG(FATAL);
00279 }
00280
00281 }
00282 }