pose_graph_trimmer.cc
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 
18 
19 #include "glog/logging.h"
20 
21 namespace cartographer {
22 namespace mapping {
23 
25  const int num_submaps_to_keep)
26  : trajectory_id_(trajectory_id), num_submaps_to_keep_(num_submaps_to_keep) {
27  CHECK_GE(num_submaps_to_keep, 3);
28 }
29 
30 void PureLocalizationTrimmer::Trim(Trimmable* const pose_graph) {
31  const int total_num_submaps = pose_graph->num_submaps(trajectory_id_);
32  while (total_num_submaps > num_submaps_trimmed_ + num_submaps_to_keep_) {
33  const int submap_index_to_trim_next = num_submaps_trimmed_;
34  pose_graph->MarkSubmapAsTrimmed(
35  SubmapId{trajectory_id_, submap_index_to_trim_next});
37  }
38 }
39 
40 } // namespace mapping
41 } // namespace cartographer
virtual void MarkSubmapAsTrimmed(const SubmapId &submap_id)=0
virtual int num_submaps(int trajectory_id) const =0
PureLocalizationTrimmer(int trajectory_id, int num_submaps_to_keep)
void Trim(Trimmable *pose_graph) override


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