00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include "cartographer/mapping/internal/2d/overlapping_submaps_trimmer_2d.h"
00018
00019 #include <algorithm>
00020
00021 #include "cartographer/mapping/2d/submap_2d.h"
00022
00023 namespace cartographer {
00024 namespace mapping {
00025 namespace {
00026
00027 class SubmapCoverageGrid2D {
00028 public:
00029
00030 using CellId = std::pair<int64 , int64 >;
00031 using StoredType = std::vector<std::pair<SubmapId, common::Time>>;
00032
00033 SubmapCoverageGrid2D(const MapLimits& map_limits)
00034 : offset_(map_limits.max()), resolution_(map_limits.resolution()) {}
00035
00036 void AddPoint(const Eigen::Vector2d& point, const SubmapId& submap_id,
00037 const common::Time& time) {
00038 CellId cell_id{common::RoundToInt64((offset_(0) - point(0)) / resolution_),
00039 common::RoundToInt64((offset_(1) - point(1)) / resolution_)};
00040 cells_[cell_id].emplace_back(submap_id, time);
00041 }
00042
00043 const std::map<CellId, StoredType>& cells() const { return cells_; }
00044 double resolution() const { return resolution_; }
00045
00046 private:
00047 Eigen::Vector2d offset_;
00048 double resolution_;
00049 std::map<CellId, StoredType> cells_;
00050 };
00051
00052
00053
00054
00055 std::set<SubmapId> AddSubmapsToSubmapCoverageGrid2D(
00056 const std::map<SubmapId, common::Time>& submap_freshness,
00057 const MapById<SubmapId, PoseGraphInterface::SubmapData>& submap_data,
00058 SubmapCoverageGrid2D* coverage_grid) {
00059 std::set<SubmapId> all_submap_ids;
00060
00061 for (const auto& submap : submap_data) {
00062 auto freshness = submap_freshness.find(submap.id);
00063 if (freshness == submap_freshness.end()) continue;
00064 if (!submap.data.submap->insertion_finished()) continue;
00065 all_submap_ids.insert(submap.id);
00066 const Grid2D& grid =
00067 *std::static_pointer_cast<const Submap2D>(submap.data.submap)->grid();
00068
00069 Eigen::Array2i offset;
00070 CellLimits cell_limits;
00071 grid.ComputeCroppedLimits(&offset, &cell_limits);
00072 if (cell_limits.num_x_cells == 0 || cell_limits.num_y_cells == 0) {
00073 LOG(WARNING) << "Empty grid found in submap ID = " << submap.id;
00074 continue;
00075 }
00076
00077 const transform::Rigid3d& global_frame_from_submap_frame = submap.data.pose;
00078 const transform::Rigid3d submap_frame_from_local_frame =
00079 submap.data.submap->local_pose().inverse();
00080 for (const Eigen::Array2i& xy_index : XYIndexRangeIterator(cell_limits)) {
00081 const Eigen::Array2i index = xy_index + offset;
00082 if (!grid.IsKnown(index)) continue;
00083
00084 const transform::Rigid3d center_of_cell_in_local_frame =
00085 transform::Rigid3d::Translation(Eigen::Vector3d(
00086 grid.limits().max().x() -
00087 grid.limits().resolution() * (index.y() + 0.5),
00088 grid.limits().max().y() -
00089 grid.limits().resolution() * (index.x() + 0.5),
00090 0));
00091
00092 const transform::Rigid2d center_of_cell_in_global_frame =
00093 transform::Project2D(global_frame_from_submap_frame *
00094 submap_frame_from_local_frame *
00095 center_of_cell_in_local_frame);
00096 coverage_grid->AddPoint(center_of_cell_in_global_frame.translation(),
00097 submap.id, freshness->second);
00098 }
00099 }
00100 return all_submap_ids;
00101 }
00102
00103
00104
00105 std::map<SubmapId, common::Time> ComputeSubmapFreshness(
00106 const MapById<SubmapId, PoseGraphInterface::SubmapData>& submap_data,
00107 const MapById<NodeId, TrajectoryNode>& trajectory_nodes,
00108 const std::vector<PoseGraphInterface::Constraint>& constraints) {
00109 std::map<SubmapId, common::Time> submap_freshness;
00110
00111
00112 std::map<SubmapId, NodeId> submap_to_latest_node;
00113 for (const PoseGraphInterface::Constraint& constraint : constraints) {
00114 if (constraint.tag != PoseGraphInterface::Constraint::INTRA_SUBMAP) {
00115 continue;
00116 }
00117 auto submap_to_node = submap_to_latest_node.find(constraint.submap_id);
00118 if (submap_to_node == submap_to_latest_node.end()) {
00119 submap_to_latest_node.insert(
00120 std::make_pair(constraint.submap_id, constraint.node_id));
00121 continue;
00122 }
00123 submap_to_node->second =
00124 std::max(submap_to_node->second, constraint.node_id);
00125 }
00126
00127
00128 for (const auto& submap_id_to_node_id : submap_to_latest_node) {
00129 auto submap_data_item = submap_data.find(submap_id_to_node_id.first);
00130 if (submap_data_item == submap_data.end()) {
00131 LOG(WARNING) << "Intra-submap constraint between SubmapID = "
00132 << submap_id_to_node_id.first << " and NodeID "
00133 << submap_id_to_node_id.second << " is missing submap data";
00134 continue;
00135 }
00136 auto latest_node_id = trajectory_nodes.find(submap_id_to_node_id.second);
00137 if (latest_node_id == trajectory_nodes.end()) continue;
00138 submap_freshness[submap_data_item->id] = latest_node_id->data.time();
00139 }
00140 return submap_freshness;
00141 }
00142
00143
00144
00145 std::vector<SubmapId> FindSubmapIdsToTrim(
00146 const SubmapCoverageGrid2D& coverage_grid,
00147 const std::set<SubmapId>& all_submap_ids, uint16 fresh_submaps_count,
00148 uint16 min_covered_cells_count) {
00149 std::map<SubmapId, uint16> submap_to_covered_cells_count;
00150 for (const auto& cell : coverage_grid.cells()) {
00151 std::vector<std::pair<SubmapId, common::Time>> submaps_per_cell(
00152 cell.second);
00153
00154
00155
00156 if (submaps_per_cell.size() > fresh_submaps_count) {
00157
00158 std::sort(submaps_per_cell.begin(), submaps_per_cell.end(),
00159 [](const std::pair<SubmapId, common::Time>& left,
00160 const std::pair<SubmapId, common::Time>& right) {
00161 return left.second > right.second;
00162 });
00163 submaps_per_cell.erase(submaps_per_cell.begin() + fresh_submaps_count,
00164 submaps_per_cell.end());
00165 }
00166 for (const std::pair<SubmapId, common::Time>& submap : submaps_per_cell) {
00167 ++submap_to_covered_cells_count[submap.first];
00168 }
00169 }
00170 std::vector<SubmapId> submap_ids_to_keep;
00171 for (const auto& id_to_cells_count : submap_to_covered_cells_count) {
00172 if (id_to_cells_count.second < min_covered_cells_count) continue;
00173 submap_ids_to_keep.push_back(id_to_cells_count.first);
00174 }
00175
00176 DCHECK(std::is_sorted(submap_ids_to_keep.begin(), submap_ids_to_keep.end()));
00177 std::vector<SubmapId> result;
00178 std::set_difference(all_submap_ids.begin(), all_submap_ids.end(),
00179 submap_ids_to_keep.begin(), submap_ids_to_keep.end(),
00180 std::back_inserter(result));
00181 return result;
00182 }
00183
00184 }
00185
00186 void OverlappingSubmapsTrimmer2D::Trim(Trimmable* pose_graph) {
00187 const auto submap_data = pose_graph->GetOptimizedSubmapData();
00188 if (submap_data.size() - current_submap_count_ <= min_added_submaps_count_) {
00189 return;
00190 }
00191
00192 const MapLimits first_submap_map_limits =
00193 std::static_pointer_cast<const Submap2D>(submap_data.begin()->data.submap)
00194 ->grid()
00195 ->limits();
00196 SubmapCoverageGrid2D coverage_grid(first_submap_map_limits);
00197 const std::map<SubmapId, common::Time> submap_freshness =
00198 ComputeSubmapFreshness(submap_data, pose_graph->GetTrajectoryNodes(),
00199 pose_graph->GetConstraints());
00200 const std::set<SubmapId> all_submap_ids = AddSubmapsToSubmapCoverageGrid2D(
00201 submap_freshness, submap_data, &coverage_grid);
00202 const std::vector<SubmapId> submap_ids_to_remove = FindSubmapIdsToTrim(
00203 coverage_grid, all_submap_ids, fresh_submaps_count_,
00204 min_covered_area_ / common::Pow2(coverage_grid.resolution()));
00205 current_submap_count_ = submap_data.size() - submap_ids_to_remove.size();
00206 for (const SubmapId& id : submap_ids_to_remove) {
00207 pose_graph->TrimSubmap(id);
00208 }
00209 }
00210
00211 }
00212 }