xray_points_processor.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2016 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
18 
19 #include <cmath>
20 #include <string>
21 
22 #include "Eigen/Core"
27 #include "cartographer/io/image.h"
31 
32 namespace cartographer {
33 namespace io {
34 namespace {
35 
36 struct PixelData {
38  float mean_r = 0.;
39  float mean_g = 0.;
40  float mean_b = 0.;
41 };
42 
43 using PixelDataMatrix =
44  Eigen::Matrix<PixelData, Eigen::Dynamic, Eigen::Dynamic>;
45 
46 float Mix(const float a, const float b, const float t) {
47  return a * (1. - t) + t * b;
48 }
49 
50 // Convert 'mat' into a pleasing-to-look-at image.
51 Image IntoImage(const PixelDataMatrix& mat) {
52  Image image(mat.cols(), mat.rows());
53  float max = std::numeric_limits<float>::min();
54  for (int y = 0; y < mat.rows(); ++y) {
55  for (int x = 0; x < mat.cols(); ++x) {
56  const PixelData& cell = mat(y, x);
57  if (cell.num_occupied_cells_in_column == 0.) {
58  continue;
59  }
60  max = std::max<float>(max, std::log(cell.num_occupied_cells_in_column));
61  }
62  }
63 
64  for (int y = 0; y < mat.rows(); ++y) {
65  for (int x = 0; x < mat.cols(); ++x) {
66  const PixelData& cell = mat(y, x);
67  if (cell.num_occupied_cells_in_column == 0.) {
68  image.SetPixel(x, y, {{255, 255, 255}});
69  continue;
70  }
71 
72  // We use a logarithmic weighting for how saturated a pixel will be. The
73  // basic idea here was that walls (full height) are fully saturated, but
74  // details like chairs and tables are still well visible.
75  const float saturation =
76  std::log(cell.num_occupied_cells_in_column) / max;
77  const FloatColor color = {{Mix(1.f, cell.mean_r, saturation),
78  Mix(1.f, cell.mean_g, saturation),
79  Mix(1.f, cell.mean_b, saturation)}};
80  image.SetPixel(x, y, ToUint8Color(color));
81  }
82  }
83  return image;
84 }
85 
86 bool ContainedIn(const common::Time& time,
87  const std::vector<mapping::Timespan>& timespans) {
88  for (const mapping::Timespan& timespan : timespans) {
89  if (timespan.start <= time && time <= timespan.end) {
90  return true;
91  }
92  }
93  return false;
94 }
95 
96 } // namespace
97 
99  const double voxel_size, const transform::Rigid3f& transform,
100  const std::vector<mapping::Floor>& floors,
101  const DrawTrajectories& draw_trajectories,
102  const std::string& output_filename,
103  const std::vector<mapping::proto::Trajectory>& trajectories,
104  FileWriterFactory file_writer_factory, PointsProcessor* const next)
105  : draw_trajectories_(draw_trajectories),
106  trajectories_(trajectories),
107  file_writer_factory_(file_writer_factory),
108  next_(next),
109  floors_(floors),
110  output_filename_(output_filename),
111  transform_(transform) {
112  for (size_t i = 0; i < (floors_.empty() ? 1 : floors.size()); ++i) {
113  aggregations_.emplace_back(
114  Aggregation{mapping::HybridGridBase<bool>(voxel_size), {}});
115  }
116 }
117 
118 std::unique_ptr<XRayPointsProcessor> XRayPointsProcessor::FromDictionary(
119  const std::vector<mapping::proto::Trajectory>& trajectories,
120  FileWriterFactory file_writer_factory,
121  common::LuaParameterDictionary* const dictionary,
122  PointsProcessor* const next) {
123  std::vector<mapping::Floor> floors;
124  const bool separate_floor = dictionary->HasKey("separate_floors") &&
125  dictionary->GetBool("separate_floors");
126  const auto draw_trajectories = (!dictionary->HasKey("draw_trajectories") ||
127  dictionary->GetBool("draw_trajectories"))
130  if (separate_floor) {
131  CHECK_EQ(trajectories.size(), 1)
132  << "Can only detect floors with a single trajectory.";
133  floors = mapping::DetectFloors(trajectories.at(0));
134  }
135 
136  return common::make_unique<XRayPointsProcessor>(
137  dictionary->GetDouble("voxel_size"),
138  transform::FromDictionary(dictionary->GetDictionary("transform").get())
139  .cast<float>(),
140  floors, draw_trajectories, dictionary->GetString("filename"),
141  trajectories, file_writer_factory, next);
142 }
143 
145  FileWriter* const file_writer) {
146  if (bounding_box_.isEmpty()) {
147  LOG(WARNING) << "Not writing output: bounding box is empty.";
148  return;
149  }
150 
151  // Returns the (x, y) pixel of the given 'index'.
152  const auto voxel_index_to_pixel =
153  [this](const Eigen::Array3i& index) -> Eigen::Array2i {
154  // We flip the y axis, since matrices rows are counted from the top.
155  return Eigen::Array2i(bounding_box_.max()[1] - index[1],
156  bounding_box_.max()[2] - index[2]);
157  };
158 
159  // Hybrid grid uses X: forward, Y: left, Z: up.
160  // For the screen we are using. X: right, Y: up
161  const int xsize = bounding_box_.sizes()[1] + 1;
162  const int ysize = bounding_box_.sizes()[2] + 1;
163  PixelDataMatrix pixel_data_matrix = PixelDataMatrix(ysize, xsize);
164  for (mapping::HybridGridBase<bool>::Iterator it(aggregation.voxels);
165  !it.Done(); it.Next()) {
166  const Eigen::Array3i cell_index = it.GetCellIndex();
167  const Eigen::Array2i pixel = voxel_index_to_pixel(cell_index);
168  PixelData& pixel_data = pixel_data_matrix(pixel.y(), pixel.x());
169  const auto& column_data = aggregation.column_data.at(
170  std::make_pair(cell_index[1], cell_index[2]));
171  pixel_data.mean_r = column_data.sum_r / column_data.count;
172  pixel_data.mean_g = column_data.sum_g / column_data.count;
173  pixel_data.mean_b = column_data.sum_b / column_data.count;
174  ++pixel_data.num_occupied_cells_in_column;
175  }
176 
177  Image image = IntoImage(pixel_data_matrix);
179  for (size_t i = 0; i < trajectories_.size(); ++i) {
181  trajectories_[i], GetColor(i),
182  [&voxel_index_to_pixel, &aggregation,
183  this](const transform::Rigid3d& pose) -> Eigen::Array2i {
184  return voxel_index_to_pixel(aggregation.voxels.GetCellIndex(
185  (transform_ * pose.cast<float>()).translation()));
186  },
187  image.GetCairoSurface().get());
188  }
189  }
190 
191  image.WritePng(file_writer);
192  CHECK(file_writer->Close());
193 }
194 
196  Aggregation* const aggregation) {
197  constexpr FloatColor kDefaultColor = {{0.f, 0.f, 0.f}};
198  for (size_t i = 0; i < batch.points.size(); ++i) {
199  const Eigen::Vector3f camera_point = transform_ * batch.points[i];
200  const Eigen::Array3i cell_index =
201  aggregation->voxels.GetCellIndex(camera_point);
202  *aggregation->voxels.mutable_value(cell_index) = true;
203  bounding_box_.extend(cell_index.matrix());
204  ColumnData& column_data =
205  aggregation->column_data[std::make_pair(cell_index[1], cell_index[2])];
206  const auto& color =
207  batch.colors.empty() ? kDefaultColor : batch.colors.at(i);
208  column_data.sum_r += color[0];
209  column_data.sum_g += color[1];
210  column_data.sum_b += color[2];
211  ++column_data.count;
212  }
213 }
214 
215 void XRayPointsProcessor::Process(std::unique_ptr<PointsBatch> batch) {
216  if (floors_.empty()) {
217  CHECK_EQ(aggregations_.size(), 1);
218  Insert(*batch, &aggregations_[0]);
219  } else {
220  for (size_t i = 0; i < floors_.size(); ++i) {
221  if (!ContainedIn(batch->start_time, floors_[i].timespans)) {
222  continue;
223  }
224  Insert(*batch, &aggregations_[i]);
225  }
226  }
227  next_->Process(std::move(batch));
228 }
229 
231  if (floors_.empty()) {
232  CHECK_EQ(aggregations_.size(), 1);
234  file_writer_factory_(output_filename_ + ".png").get());
235  } else {
236  for (size_t i = 0; i < floors_.size(); ++i) {
237  WriteVoxels(
238  aggregations_[i],
239  file_writer_factory_(output_filename_ + std::to_string(i) + ".png")
240  .get());
241  }
242  }
243 
244  switch (next_->Flush()) {
246  LOG(FATAL) << "X-Ray generation must be configured to occur after any "
247  "stages that require multiple passes.";
248 
250  return FlushResult::kFinished;
251  }
252  LOG(FATAL);
253 }
254 
255 } // namespace io
256 } // namespace cartographer
virtual void Process(std::unique_ptr< PointsBatch > points_batch)=0
std::function< std::unique_ptr< FileWriter >(const std::string &filename)> FileWriterFactory
Definition: file_writer.h:66
UniqueCairoSurfacePtr GetCairoSurface()
Definition: image.cc:99
ValueType * mutable_value(const Eigen::Array3i &index)
Definition: hybrid_grid.h:283
typename GridBase< ValueType >::Iterator Iterator
Definition: hybrid_grid.h:416
void Insert(const PointsBatch &batch, Aggregation *aggregation)
float mean_b
std::vector< FloatColor > colors
Definition: points_batch.h:65
std::map< std::pair< int, int >, ColumnData > column_data
Uint8Color ToUint8Color(const FloatColor &color)
Definition: color.h:42
Rigid3< OtherType > cast() const
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
float mean_r
XRayPointsProcessor(double voxel_size, const transform::Rigid3f &transform, const std::vector< mapping::Floor > &floors, const DrawTrajectories &draw_trajectories, const std::string &output_filename, const std::vector< mapping::proto::Trajectory > &trajectories, FileWriterFactory file_writer_factory, PointsProcessor *next)
static time_point time
FloatColor GetColor(int id)
Definition: color.cc:61
std::vector< mapping::Floor > floors_
void WritePng(FileWriter *const file_writer)
Definition: image.cc:78
std::vector< Aggregation > aggregations_
std::array< float, 3 > FloatColor
Definition: color.h:29
virtual FlushResult Flush()=0
static std::unique_ptr< XRayPointsProcessor > FromDictionary(const std::vector< mapping::proto::Trajectory > &trajectories, FileWriterFactory file_writer_factory, common::LuaParameterDictionary *dictionary, PointsProcessor *next)
transform::Rigid3d FromDictionary(common::LuaParameterDictionary *dictionary)
Eigen::Array3i GetCellIndex(const Eigen::Vector3f &point) const
Definition: hybrid_grid.h:428
size_t num_occupied_cells_in_column
const std::vector< mapping::proto::Trajectory > trajectories_
void WriteVoxels(const Aggregation &aggregation, FileWriter *const file_writer)
std::unique_ptr< LuaParameterDictionary > GetDictionary(const std::string &key)
std::vector< Floor > DetectFloors(const proto::Trajectory &trajectory)
transform::Rigid3d pose
float mean_g
void DrawTrajectory(const mapping::proto::Trajectory &trajectory, const FloatColor &color, const PoseToPixelFunction &pose_to_pixel, cairo_surface_t *surface)
std::vector< Eigen::Vector3f > points
Definition: points_batch.h:55
void Process(std::unique_ptr< PointsBatch > batch) override


cartographer
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:00:59