submap_3d.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 <limits>
21 
24 #include "glog/logging.h"
25 
26 namespace cartographer {
27 namespace mapping {
28 namespace {
29 
30 struct PixelData {
31  int min_z = INT_MAX;
32  int max_z = INT_MIN;
33  int count = 0;
34  float probability_sum = 0.f;
35  float max_probability = 0.5f;
36 };
37 
38 // Filters 'range_data', retaining only the returns that have no more than
39 // 'max_range' distance from the origin. Removes misses and reflectivity
40 // information.
41 sensor::RangeData FilterRangeDataByMaxRange(const sensor::RangeData& range_data,
42  const float max_range) {
43  sensor::RangeData result{range_data.origin, {}, {}};
44  for (const Eigen::Vector3f& hit : range_data.returns) {
45  if ((hit - range_data.origin).norm() <= max_range) {
46  result.returns.push_back(hit);
47  }
48  }
49  return result;
50 }
51 
52 std::vector<PixelData> AccumulatePixelData(
53  const int width, const int height, const Eigen::Array2i& min_index,
54  const Eigen::Array2i& max_index,
55  const std::vector<Eigen::Array4i>& voxel_indices_and_probabilities) {
56  std::vector<PixelData> accumulated_pixel_data(width * height);
57  for (const Eigen::Array4i& voxel_index_and_probability :
58  voxel_indices_and_probabilities) {
59  const Eigen::Array2i pixel_index = voxel_index_and_probability.head<2>();
60  if ((pixel_index < min_index).any() || (pixel_index > max_index).any()) {
61  // Out of bounds. This could happen because of floating point inaccuracy.
62  continue;
63  }
64  const int x = max_index.x() - pixel_index[0];
65  const int y = max_index.y() - pixel_index[1];
66  PixelData& pixel = accumulated_pixel_data[x * width + y];
67  ++pixel.count;
68  pixel.min_z = std::min(pixel.min_z, voxel_index_and_probability[2]);
69  pixel.max_z = std::max(pixel.max_z, voxel_index_and_probability[2]);
70  const float probability =
71  ValueToProbability(voxel_index_and_probability[3]);
72  pixel.probability_sum += probability;
73  pixel.max_probability = std::max(pixel.max_probability, probability);
74  }
75  return accumulated_pixel_data;
76 }
77 
78 // The first three entries of each returned value are a cell_index and the
79 // last is the corresponding probability value. We batch them together like
80 // this to only have one vector and have better cache locality.
81 std::vector<Eigen::Array4i> ExtractVoxelData(
82  const HybridGrid& hybrid_grid, const transform::Rigid3f& transform,
83  Eigen::Array2i* min_index, Eigen::Array2i* max_index) {
84  std::vector<Eigen::Array4i> voxel_indices_and_probabilities;
85  const float resolution_inverse = 1.f / hybrid_grid.resolution();
86 
87  constexpr float kXrayObstructedCellProbabilityLimit = 0.501f;
88  for (auto it = HybridGrid::Iterator(hybrid_grid); !it.Done(); it.Next()) {
89  const uint16 probability_value = it.GetValue();
90  const float probability = ValueToProbability(probability_value);
91  if (probability < kXrayObstructedCellProbabilityLimit) {
92  // We ignore non-obstructed cells.
93  continue;
94  }
95 
96  const Eigen::Vector3f cell_center_submap =
97  hybrid_grid.GetCenterOfCell(it.GetCellIndex());
98  const Eigen::Vector3f cell_center_global = transform * cell_center_submap;
99  const Eigen::Array4i voxel_index_and_probability(
100  common::RoundToInt(cell_center_global.x() * resolution_inverse),
101  common::RoundToInt(cell_center_global.y() * resolution_inverse),
102  common::RoundToInt(cell_center_global.z() * resolution_inverse),
103  probability_value);
104 
105  voxel_indices_and_probabilities.push_back(voxel_index_and_probability);
106  const Eigen::Array2i pixel_index = voxel_index_and_probability.head<2>();
107  *min_index = min_index->cwiseMin(pixel_index);
108  *max_index = max_index->cwiseMax(pixel_index);
109  }
110  return voxel_indices_and_probabilities;
111 }
112 
113 // Builds texture data containing interleaved value and alpha for the
114 // visualization from 'accumulated_pixel_data'.
115 std::string ComputePixelValues(
116  const std::vector<PixelData>& accumulated_pixel_data) {
117  std::string cell_data;
118  cell_data.reserve(2 * accumulated_pixel_data.size());
119  constexpr float kMinZDifference = 3.f;
120  constexpr float kFreeSpaceWeight = 0.15f;
121  for (const PixelData& pixel : accumulated_pixel_data) {
122  // TODO(whess): Take into account submap rotation.
123  // TODO(whess): Document the approach and make it more independent from the
124  // chosen resolution.
125  const float z_difference = pixel.count > 0 ? pixel.max_z - pixel.min_z : 0;
126  if (z_difference < kMinZDifference) {
127  cell_data.push_back(0); // value
128  cell_data.push_back(0); // alpha
129  continue;
130  }
131  const float free_space = std::max(z_difference - pixel.count, 0.f);
132  const float free_space_weight = kFreeSpaceWeight * free_space;
133  const float total_weight = pixel.count + free_space_weight;
134  const float free_space_probability = 1.f - pixel.max_probability;
135  const float average_probability = ClampProbability(
136  (pixel.probability_sum + free_space_probability * free_space_weight) /
137  total_weight);
138  const int delta = 128 - ProbabilityToLogOddsInteger(average_probability);
139  const uint8 alpha = delta > 0 ? 0 : -delta;
140  const uint8 value = delta > 0 ? delta : 0;
141  cell_data.push_back(value); // value
142  cell_data.push_back((value || alpha) ? alpha : 1); // alpha
143  }
144  return cell_data;
145 }
146 
147 void AddToTextureProto(
148  const HybridGrid& hybrid_grid, const transform::Rigid3d& global_submap_pose,
149  proto::SubmapQuery::Response::SubmapTexture* const texture) {
150  // Generate an X-ray view through the 'hybrid_grid', aligned to the
151  // xy-plane in the global map frame.
152  const float resolution = hybrid_grid.resolution();
153  texture->set_resolution(resolution);
154 
155  // Compute a bounding box for the texture.
156  Eigen::Array2i min_index(INT_MAX, INT_MAX);
157  Eigen::Array2i max_index(INT_MIN, INT_MIN);
158  const std::vector<Eigen::Array4i> voxel_indices_and_probabilities =
159  ExtractVoxelData(hybrid_grid, global_submap_pose.cast<float>(),
160  &min_index, &max_index);
161 
162  const int width = max_index.y() - min_index.y() + 1;
163  const int height = max_index.x() - min_index.x() + 1;
164  texture->set_width(width);
165  texture->set_height(height);
166 
167  const std::vector<PixelData> accumulated_pixel_data = AccumulatePixelData(
168  width, height, min_index, max_index, voxel_indices_and_probabilities);
169  const std::string cell_data = ComputePixelValues(accumulated_pixel_data);
170 
171  common::FastGzipString(cell_data, texture->mutable_cells());
172  *texture->mutable_slice_pose() = transform::ToProto(
173  global_submap_pose.inverse() *
174  transform::Rigid3d::Translation(Eigen::Vector3d(
175  max_index.x() * resolution, max_index.y() * resolution,
176  global_submap_pose.translation().z())));
177 }
178 
179 } // namespace
180 
181 proto::SubmapsOptions3D CreateSubmapsOptions3D(
182  common::LuaParameterDictionary* parameter_dictionary) {
183  proto::SubmapsOptions3D options;
184  options.set_high_resolution(
185  parameter_dictionary->GetDouble("high_resolution"));
186  options.set_high_resolution_max_range(
187  parameter_dictionary->GetDouble("high_resolution_max_range"));
188  options.set_low_resolution(parameter_dictionary->GetDouble("low_resolution"));
189  options.set_num_range_data(
190  parameter_dictionary->GetNonNegativeInt("num_range_data"));
191  *options.mutable_range_data_inserter_options() =
193  parameter_dictionary->GetDictionary("range_data_inserter").get());
194  CHECK_GT(options.num_range_data(), 0);
195  return options;
196 }
197 
198 Submap3D::Submap3D(const float high_resolution, const float low_resolution,
199  const transform::Rigid3d& local_submap_pose)
200  : Submap(local_submap_pose),
201  high_resolution_hybrid_grid_(
202  common::make_unique<HybridGrid>(high_resolution)),
203  low_resolution_hybrid_grid_(
204  common::make_unique<HybridGrid>(low_resolution)) {}
205 
206 Submap3D::Submap3D(const proto::Submap3D& proto)
207  : Submap(transform::ToRigid3(proto.local_pose())),
212  set_num_range_data(proto.num_range_data());
213  set_finished(proto.finished());
214 }
215 
216 void Submap3D::ToProto(proto::Submap* const proto,
217  bool include_probability_grid_data) const {
218  auto* const submap_3d = proto->mutable_submap_3d();
219  *submap_3d->mutable_local_pose() = transform::ToProto(local_pose());
220  submap_3d->set_num_range_data(num_range_data());
221  submap_3d->set_finished(finished());
222  if (include_probability_grid_data) {
223  *submap_3d->mutable_high_resolution_hybrid_grid() =
225  *submap_3d->mutable_low_resolution_hybrid_grid() =
227  }
228 }
229 
230 void Submap3D::UpdateFromProto(const proto::Submap& proto) {
231  CHECK(proto.has_submap_3d());
232  const auto& submap_3d = proto.submap_3d();
233  set_num_range_data(submap_3d.num_range_data());
234  set_finished(submap_3d.finished());
235  if (submap_3d.has_high_resolution_hybrid_grid()) {
237  submap_3d.has_high_resolution_hybrid_grid()
238  ? common::make_unique<HybridGrid>(
239  submap_3d.high_resolution_hybrid_grid())
240  : nullptr;
241  }
242  if (submap_3d.has_low_resolution_hybrid_grid()) {
244  submap_3d.has_low_resolution_hybrid_grid()
245  ? common::make_unique<HybridGrid>(
246  submap_3d.low_resolution_hybrid_grid())
247  : nullptr;
248  }
249 }
250 
252  const transform::Rigid3d& global_submap_pose,
253  proto::SubmapQuery::Response* const response) const {
254  response->set_submap_version(num_range_data());
255 
256  AddToTextureProto(*high_resolution_hybrid_grid_, global_submap_pose,
257  response->add_textures());
258  AddToTextureProto(*low_resolution_hybrid_grid_, global_submap_pose,
259  response->add_textures());
260 }
261 
263  const RangeDataInserter3D& range_data_inserter,
264  const int high_resolution_max_range) {
265  CHECK(!finished());
266  const sensor::RangeData transformed_range_data = sensor::TransformRangeData(
267  range_data, local_pose().inverse().cast<float>());
268  range_data_inserter.Insert(
269  FilterRangeDataByMaxRange(transformed_range_data,
270  high_resolution_max_range),
272  range_data_inserter.Insert(transformed_range_data,
275 }
276 
278  CHECK(!finished());
279  set_finished(true);
280 }
281 
282 ActiveSubmaps3D::ActiveSubmaps3D(const proto::SubmapsOptions3D& options)
283  : options_(options),
284  range_data_inserter_(options.range_data_inserter_options()) {
285  // We always want to have at least one submap which we can return and will
286  // create it at the origin in absence of a better choice.
287  //
288  // TODO(whess): Start with no submaps, so that all of them can be
289  // approximately gravity aligned.
291 }
292 
293 std::vector<std::shared_ptr<Submap3D>> ActiveSubmaps3D::submaps() const {
294  return submaps_;
295 }
296 
298 
300  const sensor::RangeData& range_data,
301  const Eigen::Quaterniond& gravity_alignment) {
302  for (auto& submap : submaps_) {
303  submap->InsertRangeData(range_data, range_data_inserter_,
304  options_.high_resolution_max_range());
305  }
306  if (submaps_.back()->num_range_data() == options_.num_range_data()) {
307  AddSubmap(transform::Rigid3d(range_data.origin.cast<double>(),
308  gravity_alignment));
309  }
310 }
311 
312 void ActiveSubmaps3D::AddSubmap(const transform::Rigid3d& local_submap_pose) {
313  if (submaps_.size() > 1) {
314  submaps_.front()->Finish();
316  submaps_.erase(submaps_.begin());
317  }
318  submaps_.emplace_back(new Submap3D(options_.high_resolution(),
319  options_.low_resolution(),
320  local_submap_pose));
321  LOG(INFO) << "Added submap " << matching_submap_index_ + submaps_.size();
322 }
323 
324 } // namespace mapping
325 } // namespace cartographer
proto::HybridGrid ToProto() const
Definition: hybrid_grid.h:528
float ClampProbability(const float probability)
proto::RangeDataInserterOptions3D CreateRangeDataInserterOptions3D(common::LuaParameterDictionary *parameter_dictionary)
std::unique_ptr< HybridGrid > high_resolution_hybrid_grid_
Definition: submap_3d.h:71
void UpdateFromProto(const proto::Submap &proto) override
Definition: submap_3d.cc:230
_Unique_if< T >::_Single_object make_unique(Args &&... args)
Definition: make_unique.h:46
const proto::SubmapsOptions3D options_
Definition: submap_3d.h:106
typename GridBase< uint16 >::Iterator Iterator
Definition: hybrid_grid.h:416
Rigid3< double > Rigid3d
const HybridGrid & high_resolution_hybrid_grid() const
Definition: submap_3d.h:56
int RoundToInt(const float x)
Definition: port.h:41
RangeDataInserter3D range_data_inserter_
Definition: submap_3d.h:109
void set_num_range_data(const int num_range_data)
Definition: submaps.h:79
void set_finished(bool finished)
Definition: submaps.h:85
float probability_sum
Definition: submap_3d.cc:34
float max_probability
Definition: submap_3d.cc:35
float ValueToProbability(const uint16 value)
const HybridGrid & low_resolution_hybrid_grid() const
Definition: submap_3d.h:59
transform::Rigid3d ToRigid3(const proto::Rigid3d &rigid)
Definition: transform.cc:71
RangeData TransformRangeData(const RangeData &range_data, const transform::Rigid3f &transform)
Definition: range_data.cc:25
void Insert(const sensor::RangeData &range_data, HybridGrid *hybrid_grid) const
uint16_t uint16
Definition: port.h:35
void ToResponseProto(const transform::Rigid3d &global_submap_pose, proto::SubmapQuery::Response *response) const override
Definition: submap_3d.cc:251
void ToProto(proto::Submap *proto, bool include_probability_grid_data) const override
Definition: submap_3d.cc:216
proto::Rigid2d ToProto(const transform::Rigid2d &transform)
Definition: transform.cc:48
proto::ProbabilityGridRangeDataInserterOptions2D options_
uint8 ProbabilityToLogOddsInteger(const float probability)
Definition: submaps.h:46
int count
Definition: submap_3d.cc:33
std::unique_ptr< ProbabilityGridRangeDataInserter2D > range_data_inserter_
std::unique_ptr< HybridGrid > low_resolution_hybrid_grid_
Definition: submap_3d.h:72
std::vector< std::shared_ptr< Submap3D > > submaps() const
Definition: submap_3d.cc:293
void InsertRangeData(const sensor::RangeData &range_data, const RangeDataInserter3D &range_data_inserter, int high_resolution_max_range)
Definition: submap_3d.cc:262
void AddSubmap(const transform::Rigid3d &local_submap_pose)
Definition: submap_3d.cc:312
proto::SubmapsOptions3D CreateSubmapsOptions3D(common::LuaParameterDictionary *parameter_dictionary)
Definition: submap_3d.cc:181
transform::Rigid3d local_pose() const
Definition: submaps.h:75
ActiveSubmaps3D(const proto::SubmapsOptions3D &options)
Definition: submap_3d.cc:282
void FastGzipString(const std::string &uncompressed, std::string *compressed)
Definition: port.h:49
std::unique_ptr< LuaParameterDictionary > GetDictionary(const std::string &key)
void InsertRangeData(const sensor::RangeData &range_data, const Eigen::Quaterniond &gravity_alignment)
Definition: submap_3d.cc:299
int num_range_data() const
Definition: submaps.h:78
std::vector< std::shared_ptr< Submap3D > > submaps_
Definition: submap_3d.h:108
int min_z
Definition: submap_3d.cc:31
static Rigid3 Translation(const Vector &vector)
Submap3D(float high_resolution, float low_resolution, const transform::Rigid3d &local_submap_pose)
Definition: submap_3d.cc:198
uint8_t uint8
Definition: port.h:34
int max_z
Definition: submap_3d.cc:32


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