17 #ifndef CARTOGRAPHER_MAPPING_POSE_GRAPH_TRIMMER_H_ 18 #define CARTOGRAPHER_MAPPING_POSE_GRAPH_TRIMMER_H_ 32 virtual int num_submaps(
int trajectory_id)
const = 0;
34 virtual std::vector<SubmapId>
GetSubmapIds(
int trajectory_id)
const = 0;
39 virtual const std::vector<PoseGraphInterface::Constraint>&
GetConstraints()
48 virtual bool IsFinished(
int trajectory_id)
const = 0;
57 virtual void Trim(
Trimmable* pose_graph) = 0;
70 void Trim(
Trimmable* pose_graph)
override;
76 bool finished_ =
false;
82 #endif // CARTOGRAPHER_MAPPING_POSE_GRAPH_TRIMMER_H_ virtual bool IsFinished(int trajectory_id) const =0
virtual const MapById< NodeId, TrajectoryNode > & GetTrajectoryNodes() const =0
~PureLocalizationTrimmer() override
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 ~PoseGraphTrimmer()
virtual std::vector< SubmapId > GetSubmapIds(int trajectory_id) const =0
virtual const std::vector< PoseGraphInterface::Constraint > & GetConstraints() const =0