pose_graph_trimmer.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #ifndef CARTOGRAPHER_MAPPING_POSE_GRAPH_TRIMMER_H_
00018 #define CARTOGRAPHER_MAPPING_POSE_GRAPH_TRIMMER_H_
00019 
00020 #include "cartographer/mapping/id.h"
00021 #include "cartographer/mapping/pose_graph_interface.h"
00022 
00023 namespace cartographer {
00024 namespace mapping {
00025 
00026 // Implemented by the pose graph to provide thread-safe access to functions for
00027 // trimming the graph.
00028 class Trimmable {
00029  public:
00030   virtual ~Trimmable() {}
00031 
00032   virtual int num_submaps(int trajectory_id) const = 0;
00033 
00034   virtual std::vector<SubmapId> GetSubmapIds(int trajectory_id) const = 0;
00035   // Returns finished submaps with optimized poses only.
00036   virtual MapById<SubmapId, PoseGraphInterface::SubmapData>
00037   GetOptimizedSubmapData() const = 0;
00038   virtual const MapById<NodeId, TrajectoryNode>& GetTrajectoryNodes() const = 0;
00039   virtual const std::vector<PoseGraphInterface::Constraint>& GetConstraints()
00040       const = 0;
00041 
00042   // Trim 'submap_id' and corresponding intra-submap nodes. They
00043   // will no longer take part in scan matching, loop closure, visualization.
00044   // The numbering remains unchanged.
00045   virtual void TrimSubmap(const SubmapId& submap_id) = 0;
00046 
00047   // Checks if the given trajectory is finished or not.
00048   virtual bool IsFinished(int trajectory_id) const = 0;
00049 
00050   // Sets the state for a specific trajectory.
00051   virtual void SetTrajectoryState(
00052       int trajectory_id, PoseGraphInterface::TrajectoryState state) = 0;
00053 };
00054 
00055 // An interface to implement algorithms that choose how to trim the pose graph.
00056 class PoseGraphTrimmer {
00057  public:
00058   virtual ~PoseGraphTrimmer() {}
00059 
00060   // Called once after each pose graph optimization.
00061   virtual void Trim(Trimmable* pose_graph) = 0;
00062 
00063   // Checks if this trimmer is in a terminatable state.
00064   virtual bool IsFinished() = 0;
00065 };
00066 
00067 // Keeps the last 'num_submaps_to_keep' of the trajectory with 'trajectory_id'
00068 // to implement localization without mapping.
00069 class PureLocalizationTrimmer : public PoseGraphTrimmer {
00070  public:
00071   PureLocalizationTrimmer(int trajectory_id, int num_submaps_to_keep);
00072   ~PureLocalizationTrimmer() override {}
00073 
00074   void Trim(Trimmable* pose_graph) override;
00075   bool IsFinished() override;
00076 
00077  private:
00078   const int trajectory_id_;
00079   int num_submaps_to_keep_;
00080   bool finished_ = false;
00081 };
00082 
00083 }  // namespace mapping
00084 }  // namespace cartographer
00085 
00086 #endif  // CARTOGRAPHER_MAPPING_POSE_GRAPH_TRIMMER_H_


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:35