17 #ifndef CARTOGRAPHER_MAPPING_2D_SPARSE_POSE_GRAPH_H_    18 #define CARTOGRAPHER_MAPPING_2D_SPARSE_POSE_GRAPH_H_    25 #include <unordered_map>    29 #include "Eigen/Geometry"    45 namespace mapping_2d {
    74                const std::vector<const mapping::Submap*>& insertion_submaps)
    79                   const Eigen::Vector3d& linear_acceleration,
    80                   const Eigen::Vector3d& angular_velocity);
    82   void AddTrimmer(std::unique_ptr<mapping::PoseGraphTrimmer> trimmer) 
override;
   115     const auto iterator = submap_ids_.find(submap);
   116     CHECK(iterator != submap_ids_.end());
   117     return iterator->second;
   123       const std::vector<const mapping::Submap*>& insertion_submaps)
   129       std::vector<const mapping::Submap*> insertion_submaps,
   156       const std::vector<std::vector<sparse_pose_graph::SubmapData>>&
   160   const mapping::proto::SparsePoseGraphOptions 
options_;
   165   std::unique_ptr<std::deque<std::function<void()>>> scan_queue_
   172   std::unordered_map<int, std::unique_ptr<common::FixedRatioSampler>>
   173       global_localization_samplers_ 
GUARDED_BY(mutex_);
   176   int num_scans_since_last_loop_closure_ 
GUARDED_BY(mutex_) = 0;
   179   bool run_loop_closure_ 
GUARDED_BY(mutex_) = 
false;
   184   std::vector<Constraint> constraints_ 
GUARDED_BY(mutex_);
   188   std::map<const mapping::Submap*, mapping::SubmapId> submap_ids_
   201   int num_trajectory_nodes_ 
GUARDED_BY(mutex_) = 0;
   204   std::vector<std::vector<sparse_pose_graph::SubmapData>>
   205       optimized_submap_transforms_ 
GUARDED_BY(mutex_);
   208   std::vector<std::unique_ptr<mapping::PoseGraphTrimmer>> trimmers_
   229 #endif  // CARTOGRAPHER_MAPPING_2D_SPARSE_POSE_GRAPH_H_ void AddTrimmer(std::unique_ptr< mapping::PoseGraphTrimmer > trimmer) override
transform::Rigid3d GetSubmapTransform(const mapping::SubmapId &submap_id) EXCLUDES(mutex_) override
void RunOptimization() EXCLUDES(mutex_)
void RunFinalOptimization() override
~SparsePoseGraph() override
std::unique_ptr< std::deque< std::function< void()> > > scan_queue_ GUARDED_BY(mutex_)
UniversalTimeScaleClock::time_point Time
SparsePoseGraph *const parent_
void AddImuData(int trajectory_id, common::Time time, const Eigen::Vector3d &linear_acceleration, const Eigen::Vector3d &angular_velocity)
void AddScan(common::Time time, const transform::Rigid3d &tracking_to_pose, const sensor::RangeData &range_data_in_pose, const transform::Rigid2d &pose, int trajectory_id, const mapping::Submap *matching_submap, const std::vector< const mapping::Submap * > &insertion_submaps) EXCLUDES(mutex_)
void GrowSubmapTransformsAsNeeded(const std::vector< const mapping::Submap * > &insertion_submaps) REQUIRES(mutex_)
~TrimmingHandle() override
SparsePoseGraph & operator=(const SparsePoseGraph &)=delete
transform::Rigid3d ComputeLocalToGlobalTransform(const std::vector< std::vector< sparse_pose_graph::SubmapData >> &submap_transforms, int trajectory_id) const REQUIRES(mutex_)
std::set< mapping::NodeId > node_ids
void ComputeConstraint(const mapping::NodeId &node_id, const mapping::SubmapId &submap_id) REQUIRES(mutex_)
std::vector< std::vector< int > > GetConnectedTrajectories() override
void WaitForAllComputations() EXCLUDES(mutex_)
const mapping::proto::SparsePoseGraphOptions options_
std::map< int, size_t > reverse_connected_components_
mapping::SubmapId GetSubmapId(const mapping::Submap *submap) const REQUIRES(mutex_)
void AddWorkItem(std::function< void()> work_item) REQUIRES(mutex_)
std::vector< std::vector< mapping::TrajectoryNode > > GetTrajectoryNodes() override EXCLUDES(mutex_)
void ComputeConstraintsForScan(const mapping::Submap *matching_submap, std::vector< const mapping::Submap * > insertion_submaps, const mapping::Submap *finished_submap, const transform::Rigid2d &pose) REQUIRES(mutex_)
std::vector< Constraint > constraints() override EXCLUDES(mutex_)
void HandleScanQueue() REQUIRES(mutex_)
std::vector< std::vector< int > > connected_components_
sparse_pose_graph::OptimizationProblem optimization_problem_
int num_submaps(int trajectory_id) EXCLUDES(mutex_) override
void ComputeConstraintsForOldScans(const mapping::Submap *submap) REQUIRES(mutex_)
transform::Rigid3d GetLocalToGlobalTransform(int trajectory_id) EXCLUDES(mutex_) override