Rename to TrimSubmap (#1192)

Trimmable::MarkSubmapAsTrimmed was incorrectly named and commented.
It really trims the submap.
master
gaschler 2018-06-12 16:01:14 +02:00 committed by Wally B. Feed
parent f79c6afee7
commit de22b9c311
9 changed files with 11 additions and 13 deletions

View File

@ -203,7 +203,7 @@ void OverlappingSubmapsTrimmer2D::Trim(Trimmable* pose_graph) {
min_covered_cells_count_); min_covered_cells_count_);
current_submap_count_ = submap_data.size() - submap_ids_to_remove.size(); current_submap_count_ = submap_data.size() - submap_ids_to_remove.size();
for (const SubmapId& id : submap_ids_to_remove) { for (const SubmapId& id : submap_ids_to_remove) {
pose_graph->MarkSubmapAsTrimmed(id); pose_graph->TrimSubmap(id);
} }
} }

View File

@ -887,8 +887,7 @@ bool PoseGraph2D::TrimmingHandle::IsFinished(const int trajectory_id) const {
return parent_->IsTrajectoryFinished(trajectory_id); return parent_->IsTrajectoryFinished(trajectory_id);
} }
void PoseGraph2D::TrimmingHandle::MarkSubmapAsTrimmed( void PoseGraph2D::TrimmingHandle::TrimSubmap(const SubmapId& submap_id) {
const SubmapId& submap_id) {
// TODO(hrapp): We have to make sure that the trajectory has been finished // TODO(hrapp): We have to make sure that the trajectory has been finished
// if we want to delete the last submaps. // if we want to delete the last submaps.
CHECK(parent_->data_.submap_data.at(submap_id).state == CHECK(parent_->data_.submap_data.at(submap_id).state ==

View File

@ -252,7 +252,7 @@ class PoseGraph2D : public PoseGraph {
REQUIRES(parent_->mutex_); REQUIRES(parent_->mutex_);
const std::vector<Constraint>& GetConstraints() const override const std::vector<Constraint>& GetConstraints() const override
REQUIRES(parent_->mutex_); REQUIRES(parent_->mutex_);
void MarkSubmapAsTrimmed(const SubmapId& submap_id) void TrimSubmap(const SubmapId& submap_id)
REQUIRES(parent_->mutex_) override; REQUIRES(parent_->mutex_) override;
bool IsFinished(int trajectory_id) const override REQUIRES(parent_->mutex_); bool IsFinished(int trajectory_id) const override REQUIRES(parent_->mutex_);

View File

@ -914,8 +914,7 @@ bool PoseGraph3D::TrimmingHandle::IsFinished(const int trajectory_id) const {
return parent_->IsTrajectoryFinished(trajectory_id); return parent_->IsTrajectoryFinished(trajectory_id);
} }
void PoseGraph3D::TrimmingHandle::MarkSubmapAsTrimmed( void PoseGraph3D::TrimmingHandle::TrimSubmap(const SubmapId& submap_id) {
const SubmapId& submap_id) {
// TODO(hrapp): We have to make sure that the trajectory has been finished // TODO(hrapp): We have to make sure that the trajectory has been finished
// if we want to delete the last submaps. // if we want to delete the last submaps.
CHECK(parent_->data_.submap_data.at(submap_id).state == CHECK(parent_->data_.submap_data.at(submap_id).state ==

View File

@ -255,7 +255,7 @@ class PoseGraph3D : public PoseGraph {
REQUIRES(parent_->mutex_); REQUIRES(parent_->mutex_);
const std::vector<Constraint>& GetConstraints() const override const std::vector<Constraint>& GetConstraints() const override
REQUIRES(parent_->mutex_); REQUIRES(parent_->mutex_);
void MarkSubmapAsTrimmed(const SubmapId& submap_id) void TrimSubmap(const SubmapId& submap_id)
REQUIRES(parent_->mutex_) override; REQUIRES(parent_->mutex_) override;
bool IsFinished(int trajectory_id) const override REQUIRES(parent_->mutex_); bool IsFinished(int trajectory_id) const override REQUIRES(parent_->mutex_);

View File

@ -203,7 +203,7 @@ class EvenSubmapTrimmer : public PoseGraphTrimmer {
auto submap_ids = pose_graph->GetSubmapIds(trajectory_id_); auto submap_ids = pose_graph->GetSubmapIds(trajectory_id_);
for (const auto submap_id : submap_ids) { for (const auto submap_id : submap_ids) {
if (submap_id.submap_index % 2 == 0) { if (submap_id.submap_index % 2 == 0) {
pose_graph->MarkSubmapAsTrimmed(submap_id); pose_graph->TrimSubmap(submap_id);
} }
} }
} }

View File

@ -90,7 +90,7 @@ class FakeTrimmable : public Trimmable {
return constraints_; return constraints_;
} }
void MarkSubmapAsTrimmed(const SubmapId& submap_id) override { void TrimSubmap(const SubmapId& submap_id) override {
trimmed_submaps_.push_back(submap_id); trimmed_submaps_.push_back(submap_id);
} }

View File

@ -34,7 +34,7 @@ void PureLocalizationTrimmer::Trim(Trimmable* const pose_graph) {
auto submap_ids = pose_graph->GetSubmapIds(trajectory_id_); auto submap_ids = pose_graph->GetSubmapIds(trajectory_id_);
for (std::size_t i = 0; i + num_submaps_to_keep_ < submap_ids.size(); ++i) { for (std::size_t i = 0; i + num_submaps_to_keep_ < submap_ids.size(); ++i) {
pose_graph->MarkSubmapAsTrimmed(submap_ids.at(i)); pose_graph->TrimSubmap(submap_ids.at(i));
} }
if (num_submaps_to_keep_ == 0) { if (num_submaps_to_keep_ == 0) {

View File

@ -39,10 +39,10 @@ class Trimmable {
virtual const std::vector<PoseGraphInterface::Constraint>& GetConstraints() virtual const std::vector<PoseGraphInterface::Constraint>& GetConstraints()
const = 0; const = 0;
// Marks 'submap_id' and corresponding intra-submap nodes as trimmed. They // Trim 'submap_id' and corresponding intra-submap nodes. They
// will no longer take part in scan matching, loop closure, visualization. // will no longer take part in scan matching, loop closure, visualization.
// Submaps and nodes are only marked, the numbering remains unchanged. // The numbering remains unchanged.
virtual void MarkSubmapAsTrimmed(const SubmapId& submap_id) = 0; virtual void TrimSubmap(const SubmapId& submap_id) = 0;
// Checks if the given trajectory is finished or not. // Checks if the given trajectory is finished or not.
virtual bool IsFinished(int trajectory_id) const = 0; virtual bool IsFinished(int trajectory_id) const = 0;