overlapping_submaps_trimmer_2d.cc
Go to the documentation of this file.
1 /*
2  * Copyright 2018 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 <algorithm>
20 
22 
23 namespace cartographer {
24 namespace mapping {
25 namespace {
26 
27 class SubmapCoverageGrid2D {
28  public:
29  // Aliases for documentation only (no type-safety).
30  using CellId = std::pair<int64 /* x cells */, int64 /* y cells */>;
31  using StoredType = std::vector<std::pair<SubmapId, common::Time>>;
32 
33  SubmapCoverageGrid2D(const MapLimits& map_limits)
34  : offset_(map_limits.max()), resolution_(map_limits.resolution()) {}
35 
36  void AddPoint(const Eigen::Vector2d& point, const SubmapId& submap_id,
37  const common::Time& time) {
38  CellId cell_id{common::RoundToInt64((offset_(0) - point(0)) / resolution_),
39  common::RoundToInt64((offset_(1) - point(1)) / resolution_)};
40  cells_[cell_id].emplace_back(submap_id, time);
41  }
42 
43  const std::map<CellId, StoredType>& cells() const { return cells_; }
44 
45  private:
46  Eigen::Vector2d offset_;
47  double resolution_;
48  std::map<CellId, StoredType> cells_;
49 };
50 
51 // Iterates over every cell in a submap, transforms the center of the cell to
52 // the global frame and then adds the submap id and the timestamp of the most
53 // recent range data insertion into the global grid.
54 std::set<SubmapId> AddSubmapsToSubmapCoverageGrid2D(
55  const std::map<SubmapId, common::Time>& submap_freshness,
56  const MapById<SubmapId, PoseGraphInterface::SubmapData>& submap_data,
57  SubmapCoverageGrid2D* coverage_grid) {
58  std::set<SubmapId> all_submap_ids;
59 
60  for (const auto& submap : submap_data) {
61  auto freshness = submap_freshness.find(submap.id);
62  if (freshness == submap_freshness.end()) continue;
63  if (!submap.data.submap->finished()) continue;
64  all_submap_ids.insert(submap.id);
65  const Grid2D& grid =
66  *std::static_pointer_cast<const Submap2D>(submap.data.submap)->grid();
67  // Iterate over every cell in a submap.
68  Eigen::Array2i offset;
69  CellLimits cell_limits;
70  grid.ComputeCroppedLimits(&offset, &cell_limits);
71  if (cell_limits.num_x_cells == 0 || cell_limits.num_y_cells == 0) {
72  LOG(WARNING) << "Empty grid found in submap ID = " << submap.id;
73  continue;
74  }
75 
76  const transform::Rigid3d& global_frame_from_submap_frame = submap.data.pose;
77  const transform::Rigid3d submap_frame_from_local_frame =
78  submap.data.submap->local_pose().inverse();
79  for (const Eigen::Array2i& xy_index : XYIndexRangeIterator(cell_limits)) {
80  const Eigen::Array2i index = xy_index + offset;
81  if (!grid.IsKnown(index)) continue;
82 
83  const transform::Rigid3d center_of_cell_in_local_frame =
84  transform::Rigid3d::Translation(Eigen::Vector3d(
85  grid.limits().max().x() -
86  grid.limits().resolution() * (index.y() + 0.5),
87  grid.limits().max().y() -
88  grid.limits().resolution() * (index.x() + 0.5),
89  0));
90 
91  const transform::Rigid2d center_of_cell_in_global_frame =
92  transform::Project2D(global_frame_from_submap_frame *
93  submap_frame_from_local_frame *
94  center_of_cell_in_local_frame);
95  coverage_grid->AddPoint(center_of_cell_in_global_frame.translation(),
96  submap.id, freshness->second);
97  }
98  }
99  return all_submap_ids;
100 }
101 
102 // Uses intra-submap constraints and trajectory node timestamps to identify time
103 // of the last range data insertion to the submap.
104 std::map<SubmapId, common::Time> ComputeSubmapFreshness(
105  const MapById<SubmapId, PoseGraphInterface::SubmapData>& submap_data,
106  const MapById<NodeId, TrajectoryNode>& trajectory_nodes,
107  const std::vector<PoseGraphInterface::Constraint>& constraints) {
108  std::map<SubmapId, common::Time> submap_freshness;
109 
110  // Find the node with the largest NodeId per SubmapId.
111  std::map<SubmapId, NodeId> submap_to_latest_node;
112  for (const PoseGraphInterface::Constraint& constraint : constraints) {
113  if (constraint.tag != PoseGraphInterface::Constraint::INTRA_SUBMAP) {
114  continue;
115  }
116  auto submap_to_node = submap_to_latest_node.find(constraint.submap_id);
117  if (submap_to_node == submap_to_latest_node.end()) {
118  submap_to_latest_node.insert(
119  std::make_pair(constraint.submap_id, constraint.node_id));
120  continue;
121  }
122  submap_to_node->second =
123  std::max(submap_to_node->second, constraint.node_id);
124  }
125 
126  // Find timestamp of every latest node.
127  for (const auto& submap_id_to_node_id : submap_to_latest_node) {
128  auto submap_data_item = submap_data.find(submap_id_to_node_id.first);
129  if (submap_data_item == submap_data.end()) {
130  LOG(WARNING) << "Intra-submap constraint between SubmapID = "
131  << submap_id_to_node_id.first << " and NodeID "
132  << submap_id_to_node_id.second << " is missing submap data";
133  continue;
134  }
135  auto latest_node_id = trajectory_nodes.find(submap_id_to_node_id.second);
136  if (latest_node_id == trajectory_nodes.end()) continue;
137  submap_freshness[submap_data_item->id] = latest_node_id->data.time();
138  }
139  return submap_freshness;
140 }
141 
142 // Returns IDs of submaps that have less than 'min_covered_cells_count' cells
143 // not overlapped by at least 'fresh_submaps_count' submaps.
144 std::vector<SubmapId> FindSubmapIdsToTrim(
145  const SubmapCoverageGrid2D& coverage_grid,
146  const std::set<SubmapId>& all_submap_ids, uint16 fresh_submaps_count,
147  uint16 min_covered_cells_count) {
148  std::map<SubmapId, uint16> submap_to_covered_cells_count;
149  for (const auto& cell : coverage_grid.cells()) {
150  std::vector<std::pair<SubmapId, common::Time>> submaps_per_cell(
151  cell.second);
152 
153  // In case there are several submaps covering the cell, only the freshest
154  // submaps are kept.
155  if (submaps_per_cell.size() > fresh_submaps_count) {
156  // Sort by time in descending order.
157  std::sort(submaps_per_cell.begin(), submaps_per_cell.end(),
158  [](const std::pair<SubmapId, common::Time>& left,
159  const std::pair<SubmapId, common::Time>& right) {
160  return left.second > right.second;
161  });
162  submaps_per_cell.erase(submaps_per_cell.begin() + fresh_submaps_count,
163  submaps_per_cell.end());
164  }
165  for (const std::pair<SubmapId, common::Time>& submap : submaps_per_cell) {
166  ++submap_to_covered_cells_count[submap.first];
167  }
168  }
169  std::vector<SubmapId> submap_ids_to_keep;
170  for (const auto& id_to_cells_count : submap_to_covered_cells_count) {
171  if (id_to_cells_count.second < min_covered_cells_count) continue;
172  submap_ids_to_keep.push_back(id_to_cells_count.first);
173  }
174 
175  DCHECK(std::is_sorted(submap_ids_to_keep.begin(), submap_ids_to_keep.end()));
176  std::vector<SubmapId> result;
177  std::set_difference(all_submap_ids.begin(), all_submap_ids.end(),
178  submap_ids_to_keep.begin(), submap_ids_to_keep.end(),
179  std::back_inserter(result));
180  return result;
181 }
182 
183 } // namespace
184 
186  const auto submap_data = pose_graph->GetOptimizedSubmapData();
187  if (submap_data.size() - current_submap_count_ <= min_added_submaps_count_) {
188  return;
189  }
190 
191  const MapLimits first_submap_map_limits =
192  std::static_pointer_cast<const Submap2D>(submap_data.begin()->data.submap)
193  ->grid()
194  ->limits();
195  SubmapCoverageGrid2D coverage_grid(first_submap_map_limits);
196  const std::map<SubmapId, common::Time> submap_freshness =
197  ComputeSubmapFreshness(submap_data, pose_graph->GetTrajectoryNodes(),
198  pose_graph->GetConstraints());
199  const std::set<SubmapId> all_submap_ids = AddSubmapsToSubmapCoverageGrid2D(
200  submap_freshness, submap_data, &coverage_grid);
201  const std::vector<SubmapId> submap_ids_to_remove =
202  FindSubmapIdsToTrim(coverage_grid, all_submap_ids, fresh_submaps_count_,
203  min_covered_cells_count_);
204  current_submap_count_ = submap_data.size() - submap_ids_to_remove.size();
205  for (const SubmapId& id : submap_ids_to_remove) {
206  pose_graph->MarkSubmapAsTrimmed(id);
207  }
208 }
209 
210 } // namespace mapping
211 } // namespace cartographer
virtual const MapById< NodeId, TrajectoryNode > & GetTrajectoryNodes() const =0
Rigid3< double > Rigid3d
virtual void MarkSubmapAsTrimmed(const SubmapId &submap_id)=0
int64_t int64
Definition: port.h:33
UniversalTimeScaleClock::time_point Time
Definition: time.h:44
std::map< CellId, StoredType > cells_
Rigid2< T > Project2D(const Rigid3< T > &transform)
Definition: transform.h:103
Rigid2< double > Rigid2d
uint16_t uint16
Definition: port.h:35
static time_point time
virtual MapById< SubmapId, PoseGraphInterface::SubmapData > GetOptimizedSubmapData() const =0
Eigen::Vector2d offset_
int64 RoundToInt64(const float x)
Definition: port.h:45
static Rigid3 Translation(const Vector &vector)
virtual const std::vector< PoseGraphInterface::Constraint > & GetConstraints() const =0


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