pose_graph_trimmer.h
Go to the documentation of this file.
1 /*
2  * Copyright 2016 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 
17 #ifndef CARTOGRAPHER_MAPPING_POSE_GRAPH_TRIMMER_H_
18 #define CARTOGRAPHER_MAPPING_POSE_GRAPH_TRIMMER_H_
19 
22 
23 namespace cartographer {
24 namespace mapping {
25 
26 // Implemented by the pose graph to provide thread-safe access to functions for
27 // trimming the graph.
28 class Trimmable {
29  public:
30  virtual ~Trimmable() {}
31 
32  virtual int num_submaps(int trajectory_id) const = 0;
33 
34  virtual std::vector<SubmapId> GetSubmapIds(int trajectory_id) const = 0;
35  // Returns finished submaps with optimized poses only.
37  GetOptimizedSubmapData() const = 0;
38  virtual const MapById<NodeId, TrajectoryNode>& GetTrajectoryNodes() const = 0;
39  virtual const std::vector<PoseGraphInterface::Constraint>& GetConstraints()
40  const = 0;
41 
42  // Marks 'submap_id' and corresponding intra-submap nodes as trimmed. They
43  // will no longer take part in scan matching, loop closure, visualization.
44  // Submaps and nodes are only marked, the numbering remains unchanged.
45  virtual void MarkSubmapAsTrimmed(const SubmapId& submap_id) = 0;
46 
47  // Checks if the given trajectory is finished or not.
48  virtual bool IsFinished(int trajectory_id) const = 0;
49 };
50 
51 // An interface to implement algorithms that choose how to trim the pose graph.
53  public:
54  virtual ~PoseGraphTrimmer() {}
55 
56  // Called once after each pose graph optimization.
57  virtual void Trim(Trimmable* pose_graph) = 0;
58 
59  // Checks if this trimmer is in a terminatable state.
60  virtual bool IsFinished() = 0;
61 };
62 
63 // Keeps the last 'num_submaps_to_keep' of the trajectory with 'trajectory_id'
64 // to implement localization without mapping.
66  public:
67  PureLocalizationTrimmer(int trajectory_id, int num_submaps_to_keep);
69 
70  void Trim(Trimmable* pose_graph) override;
71  bool IsFinished() override;
72 
73  private:
74  const int trajectory_id_;
76  bool finished_ = false;
77 };
78 
79 } // namespace mapping
80 } // namespace cartographer
81 
82 #endif // CARTOGRAPHER_MAPPING_POSE_GRAPH_TRIMMER_H_
virtual bool IsFinished(int trajectory_id) const =0
virtual const MapById< NodeId, TrajectoryNode > & GetTrajectoryNodes() const =0
virtual void MarkSubmapAsTrimmed(const SubmapId &submap_id)=0
virtual int num_submaps(int trajectory_id) const =0
virtual MapById< SubmapId, PoseGraphInterface::SubmapData > GetOptimizedSubmapData() const =0
virtual std::vector< SubmapId > GetSubmapIds(int trajectory_id) const =0
virtual const std::vector< PoseGraphInterface::Constraint > & GetConstraints() const =0


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