Allow trimmer to get nodes/constraints. (#1034)

* Allow trimmer to get nodes/constraints.

* Mark the methods const.
master
Alexander Belyaev 2018-04-04 12:50:12 +02:00 committed by GitHub
parent 41fc7e38cc
commit abb2661b76
No known key found for this signature in database
GPG Key ID: 4AEE18F83AFDEB23
6 changed files with 35 additions and 0 deletions

View File

@ -798,6 +798,16 @@ std::vector<SubmapId> PoseGraph2D::TrimmingHandle::GetSubmapIds(
return submap_ids;
}
MapById<NodeId, TrajectoryNode>
PoseGraph2D::TrimmingHandle::GetTrajectoryNodes() const {
return parent_->trajectory_nodes_;
}
std::vector<PoseGraphInterface::Constraint>
PoseGraph2D::TrimmingHandle::GetConstraints() const {
return parent_->constraints_;
}
bool PoseGraph2D::TrimmingHandle::IsFinished(const int trajectory_id) const {
return parent_->IsTrajectoryFinished(trajectory_id);
}

View File

@ -283,6 +283,8 @@ class PoseGraph2D : public PoseGraph {
std::vector<SubmapId> GetSubmapIds(int trajectory_id) const override;
MapById<SubmapId, PoseGraphInterface::SubmapData> GetAllSubmapData()
const override;
MapById<NodeId, TrajectoryNode> GetTrajectoryNodes() const override;
std::vector<PoseGraphInterface::Constraint> GetConstraints() const override;
void MarkSubmapAsTrimmed(const SubmapId& submap_id)
REQUIRES(parent_->mutex_) override;
bool IsFinished(int trajectory_id) const override;

View File

@ -828,6 +828,16 @@ PoseGraph3D::TrimmingHandle::GetAllSubmapData() const {
return parent_->GetSubmapDataUnderLock();
}
MapById<NodeId, TrajectoryNode>
PoseGraph3D::TrimmingHandle::GetTrajectoryNodes() const {
return parent_->trajectory_nodes_;
}
std::vector<PoseGraphInterface::Constraint>
PoseGraph3D::TrimmingHandle::GetConstraints() const {
return parent_->constraints_;
}
bool PoseGraph3D::TrimmingHandle::IsFinished(const int trajectory_id) const {
return parent_->IsTrajectoryFinished(trajectory_id);
}

View File

@ -288,6 +288,8 @@ class PoseGraph3D : public PoseGraph {
std::vector<SubmapId> GetSubmapIds(int trajectory_id) const override;
MapById<SubmapId, PoseGraphInterface::SubmapData> GetAllSubmapData()
const override;
MapById<NodeId, TrajectoryNode> GetTrajectoryNodes() const override;
std::vector<PoseGraphInterface::Constraint> GetConstraints() const override;
void MarkSubmapAsTrimmed(const SubmapId& submap_id)
REQUIRES(parent_->mutex_) override;
bool IsFinished(int trajectory_id) const override;

View File

@ -34,6 +34,9 @@ class Trimmable {
virtual std::vector<SubmapId> GetSubmapIds(int trajectory_id) const = 0;
virtual MapById<SubmapId, PoseGraphInterface::SubmapData> GetAllSubmapData()
const = 0;
virtual MapById<NodeId, TrajectoryNode> GetTrajectoryNodes() const = 0;
virtual std::vector<PoseGraphInterface::Constraint> GetConstraints()
const = 0;
// Marks 'submap_id' and corresponding intra-submap nodes as trimmed. They
// will no longer take part in scan matching, loop closure, visualization.

View File

@ -47,6 +47,14 @@ class FakePoseGraph : public Trimmable {
return {};
}
MapById<NodeId, TrajectoryNode> GetTrajectoryNodes() const override {
return {};
}
std::vector<PoseGraphInterface::Constraint> GetConstraints() const override {
return {};
}
void MarkSubmapAsTrimmed(const SubmapId& submap_id) override {
trimmed_submaps_.push_back(submap_id);
}