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 
21 
22 namespace cartographer {
23 namespace mapping {
24 
25 // Implemented by the pose graph to provide thread-safe access to functions for
26 // trimming the graph.
27 class Trimmable {
28  public:
29  virtual ~Trimmable() {}
30 
31  // TODO(whess): This is all the functionality necessary for pure localization.
32  // To be expanded as needed for lifelong mapping.
33  virtual int num_submaps(int trajectory_id) const = 0;
34 
35  // Marks 'submap_id' and corresponding intra-submap nodes as trimmed. They
36  // will no longer take part in scan matching, loop closure, visualization.
37  // Submaps and nodes are only marked, the numbering remains unchanged.
38  virtual void MarkSubmapAsTrimmed(const SubmapId& submap_id) = 0;
39 };
40 
41 // An interface to implement algorithms that choose how to trim the pose graph.
43  public:
44  virtual ~PoseGraphTrimmer() {}
45 
46  // Called once after each pose graph optimization.
47  virtual void Trim(Trimmable* pose_graph) = 0;
48 };
49 
50 // Keeps the last 'num_submaps_to_keep' of the trajectory with 'trajectory_id'
51 // to implement localization without mapping.
53  public:
54  PureLocalizationTrimmer(int trajectory_id, int num_submaps_to_keep);
56 
57  void Trim(Trimmable* pose_graph) override;
58 
59  private:
60  const int trajectory_id_;
62  int num_submaps_trimmed_ = 0;
63 };
64 
65 } // namespace mapping
66 } // namespace cartographer
67 
68 #endif // CARTOGRAPHER_MAPPING_POSE_GRAPH_TRIMMER_H_
virtual void MarkSubmapAsTrimmed(const SubmapId &submap_id)=0
virtual int num_submaps(int trajectory_id) const =0


cartographer
Author(s):
autogenerated on Mon Jun 10 2019 12:51:39