diff --git a/cartographer/mapping/internal/2d/pose_graph_2d.cc b/cartographer/mapping/internal/2d/pose_graph_2d.cc index 7827fc4..c832a4b 100644 --- a/cartographer/mapping/internal/2d/pose_graph_2d.cc +++ b/cartographer/mapping/internal/2d/pose_graph_2d.cc @@ -716,12 +716,7 @@ PoseGraph::SubmapData PoseGraph2D::GetSubmapData(const SubmapId& submap_id) { MapById PoseGraph2D::GetAllSubmapData() { common::MutexLocker locker(&mutex_); - MapById submaps; - for (const auto& submap_id_data : submap_data_) { - submaps.Insert(submap_id_data.id, - GetSubmapDataUnderLock(submap_id_data.id)); - } - return submaps; + return GetSubmapDataUnderLock(); } MapById @@ -788,6 +783,11 @@ int PoseGraph2D::TrimmingHandle::num_submaps(const int trajectory_id) const { return submap_data.SizeOfTrajectoryOrZero(trajectory_id); } +MapById +PoseGraph2D::TrimmingHandle::GetAllSubmapData() const { + return parent_->GetSubmapDataUnderLock(); +} + std::vector PoseGraph2D::TrimmingHandle::GetSubmapIds( int trajectory_id) const { std::vector submap_ids; @@ -860,5 +860,15 @@ void PoseGraph2D::TrimmingHandle::MarkSubmapAsTrimmed( } } +MapById +PoseGraph2D::GetSubmapDataUnderLock() { + MapById submaps; + for (const auto& submap_id_data : submap_data_) { + submaps.Insert(submap_id_data.id, + GetSubmapDataUnderLock(submap_id_data.id)); + } + return submaps; +} + } // namespace mapping } // namespace cartographer diff --git a/cartographer/mapping/internal/2d/pose_graph_2d.h b/cartographer/mapping/internal/2d/pose_graph_2d.h index c0e4c80..fa832e1 100644 --- a/cartographer/mapping/internal/2d/pose_graph_2d.h +++ b/cartographer/mapping/internal/2d/pose_graph_2d.h @@ -153,6 +153,8 @@ class PoseGraph2D : public PoseGraph { SubmapState state = SubmapState::kActive; }; + MapById GetSubmapDataUnderLock(); + // Handles a new work item. void AddWorkItem(const std::function& work_item) REQUIRES(mutex_); @@ -279,6 +281,8 @@ class PoseGraph2D : public PoseGraph { int num_submaps(int trajectory_id) const override; std::vector GetSubmapIds(int trajectory_id) const override; + MapById GetAllSubmapData() + const override; void MarkSubmapAsTrimmed(const SubmapId& submap_id) REQUIRES(parent_->mutex_) override; bool IsFinished(int trajectory_id) const override; diff --git a/cartographer/mapping/internal/3d/pose_graph_3d.cc b/cartographer/mapping/internal/3d/pose_graph_3d.cc index 8fb1dc6..9be67a5 100644 --- a/cartographer/mapping/internal/3d/pose_graph_3d.cc +++ b/cartographer/mapping/internal/3d/pose_graph_3d.cc @@ -749,12 +749,7 @@ PoseGraph::SubmapData PoseGraph3D::GetSubmapData(const SubmapId& submap_id) { MapById PoseGraph3D::GetAllSubmapData() { common::MutexLocker locker(&mutex_); - MapById submaps; - for (const auto& submap_id_data : submap_data_) { - submaps.Insert(submap_id_data.id, - GetSubmapDataUnderLock(submap_id_data.id)); - } - return submaps; + return GetSubmapDataUnderLock(); } MapById @@ -828,6 +823,10 @@ std::vector PoseGraph3D::TrimmingHandle::GetSubmapIds( } return submap_ids; } +MapById +PoseGraph3D::TrimmingHandle::GetAllSubmapData() const { + return parent_->GetSubmapDataUnderLock(); +} bool PoseGraph3D::TrimmingHandle::IsFinished(const int trajectory_id) const { return parent_->IsTrajectoryFinished(trajectory_id); @@ -891,5 +890,15 @@ void PoseGraph3D::TrimmingHandle::MarkSubmapAsTrimmed( } } +MapById +PoseGraph3D::GetSubmapDataUnderLock() { + MapById submaps; + for (const auto& submap_id_data : submap_data_) { + submaps.Insert(submap_id_data.id, + GetSubmapDataUnderLock(submap_id_data.id)); + } + return submaps; +} + } // namespace mapping } // namespace cartographer diff --git a/cartographer/mapping/internal/3d/pose_graph_3d.h b/cartographer/mapping/internal/3d/pose_graph_3d.h index 01ea013..da00050 100644 --- a/cartographer/mapping/internal/3d/pose_graph_3d.h +++ b/cartographer/mapping/internal/3d/pose_graph_3d.h @@ -158,6 +158,8 @@ class PoseGraph3D : public PoseGraph { SubmapState state = SubmapState::kActive; }; + MapById GetSubmapDataUnderLock(); + // Handles a new work item. void AddWorkItem(const std::function& work_item) REQUIRES(mutex_); @@ -284,6 +286,8 @@ class PoseGraph3D : public PoseGraph { int num_submaps(int trajectory_id) const override; std::vector GetSubmapIds(int trajectory_id) const override; + MapById GetAllSubmapData() + const override; void MarkSubmapAsTrimmed(const SubmapId& submap_id) REQUIRES(parent_->mutex_) override; bool IsFinished(int trajectory_id) const override; diff --git a/cartographer/mapping/pose_graph_trimmer.h b/cartographer/mapping/pose_graph_trimmer.h index 5bb5936..82a05f5 100644 --- a/cartographer/mapping/pose_graph_trimmer.h +++ b/cartographer/mapping/pose_graph_trimmer.h @@ -18,6 +18,7 @@ #define CARTOGRAPHER_MAPPING_POSE_GRAPH_TRIMMER_H_ #include "cartographer/mapping/id.h" +#include "cartographer/mapping/pose_graph_interface.h" namespace cartographer { namespace mapping { @@ -31,6 +32,8 @@ class Trimmable { virtual int num_submaps(int trajectory_id) const = 0; virtual std::vector GetSubmapIds(int trajectory_id) const = 0; + virtual MapById GetAllSubmapData() + const = 0; // Marks 'submap_id' and corresponding intra-submap nodes as trimmed. They // will no longer take part in scan matching, loop closure, visualization. diff --git a/cartographer/mapping/pose_graph_trimmer_test.cc b/cartographer/mapping/pose_graph_trimmer_test.cc index bcd7ac0..6bdcd0f 100644 --- a/cartographer/mapping/pose_graph_trimmer_test.cc +++ b/cartographer/mapping/pose_graph_trimmer_test.cc @@ -42,6 +42,11 @@ class FakePoseGraph : public Trimmable { return submaps_; } + MapById GetAllSubmapData() + const override { + return {}; + } + void MarkSubmapAsTrimmed(const SubmapId& submap_id) override { trimmed_submaps_.push_back(submap_id); }