17 #ifndef CARTOGRAPHER_MAPPING_INTERNAL_2D_POSE_GRAPH_2D_H_ 18 #define CARTOGRAPHER_MAPPING_INTERNAL_2D_POSE_GRAPH_2D_H_ 26 #include <unordered_map> 30 #include "Eigen/Geometry" 63 const proto::PoseGraphOptions& options,
64 std::unique_ptr<optimization::OptimizationProblem2D> optimization_problem,
77 std::shared_ptr<const TrajectoryNode::Data> constant_data,
79 const std::vector<std::shared_ptr<const Submap2D>>& insertion_submaps)
100 const proto::Submap& submap)
override;
102 const proto::Node& node)
override;
105 const SubmapId& submap_id)
override;
107 const std::vector<Constraint>&
constraints)
override;
108 void AddTrimmer(std::unique_ptr<PoseGraphTrimmer> trimmer)
override;
168 void AddWorkItem(const std::function<
void()>& work_item) REQUIRES(mutex_);
176 int trajectory_id, const common::
Time time,
177 const std::vector<std::shared_ptr<const
Submap2D>>& insertion_submaps)
183 std::vector<std::shared_ptr<const
Submap2D>> insertion_submaps,
184 bool newly_finished_submap) REQUIRES(mutex_);
195 void HandleWorkQueue(const constraints::ConstraintBuilder2D::Result& result)
209 const
MapById<
SubmapId, optimization::SubmapSpec2D>& global_submap_poses,
210 int trajectory_id) const REQUIRES(mutex_);
216 const SubmapId& submap_id) const
225 mutable common::Mutex mutex_;
229 std::unique_ptr<std::deque<std::function<
void()>>> work_queue_
236 std::unordered_map<
int, std::unique_ptr<common::FixedRatioSampler>>
237 global_localization_samplers_
GUARDED_BY(mutex_);
240 int num_nodes_since_last_loop_closure_
GUARDED_BY(mutex_) = 0;
243 bool run_loop_closure_
GUARDED_BY(mutex_) = false;
259 int num_trajectory_nodes_
GUARDED_BY(mutex_) = 0;
262 MapById<SubmapId, optimization::SubmapSpec2D> global_submap_poses_
273 std::set<
int> frozen_trajectories_
GUARDED_BY(mutex_);
276 std::set<
int> finished_trajectories_
GUARDED_BY(mutex_);
289 int num_submaps(
int trajectory_id)
const override;
290 std::vector<SubmapId> GetSubmapIds(
int trajectory_id)
const override;
295 const std::vector<Constraint>& GetConstraints()
const override 297 void MarkSubmapAsTrimmed(
const SubmapId& submap_id)
299 bool IsFinished(
int trajectory_id)
const override REQUIRES(parent_->mutex_);
309 #endif // CARTOGRAPHER_MAPPING_INTERNAL_2D_POSE_GRAPH_2D_H_ MapById< NodeId, TrajectoryNodePose > GetTrajectoryNodePoses() const override EXCLUDES(mutex_)
common::Time GetLatestNodeTime(const NodeId &node_id, const SubmapId &submap_id) const REQUIRES(mutex_)
TrajectoryConnectivityState trajectory_connectivity_state_
void FreezeTrajectory(int trajectory_id) override
std::unique_ptr< optimization::OptimizationProblem2D > optimization_problem_
PoseGraph2D(const proto::PoseGraphOptions &options, std::unique_ptr< optimization::OptimizationProblem2D > optimization_problem, common::ThreadPool *thread_pool)
transform::Rigid3d GetLocalToGlobalTransform(int trajectory_id) const EXCLUDES(mutex_) override
std::unique_ptr< ConstraintBuilder2D > constraint_builder_
void AddNodeFromProto(const transform::Rigid3d &global_pose, const proto::Node &node) override
void AddTrimmer(std::unique_ptr< PoseGraphTrimmer > trimmer) override
~TrimmingHandle() override
void ComputeConstraint(const NodeId &node_id, const SubmapId &submap_id) REQUIRES(mutex_)
void AddNodeToSubmap(const NodeId &node_id, const SubmapId &submap_id) override
std::function< void(const std::map< int, SubmapId > &, const std::map< int, NodeId > &)> GlobalSlamOptimizationCallback
MapById< SubmapId, PoseGraphInterface::SubmapData > GetSubmapDataUnderLock() const REQUIRES(mutex_)
void AddSerializedConstraints(const std::vector< Constraint > &constraints) override
std::vector< Constraint > constraints() const override EXCLUDES(mutex_)
const proto::PoseGraphOptions options_
UniversalTimeScaleClock::time_point Time
sensor::MapByTime< sensor::OdometryData > GetOdometryData() const override EXCLUDES(mutex_)
void WaitForAllComputations() EXCLUDES(mutex_)
std::shared_ptr< const Submap2D > submap
void AddLandmarkData(int trajectory_id, const sensor::LandmarkData &landmark_data) override EXCLUDES(mutex_)
sensor::MapByTime< sensor::FixedFramePoseData > GetFixedFramePoseData() const override EXCLUDES(mutex_)
bool IsTrajectoryFinished(int trajectory_id) const override REQUIRES(mutex_)
PoseGraph2D *const parent_
std::vector< SubmapId > InitializeGlobalSubmapPoses(int trajectory_id, const common::Time time, const std::vector< std::shared_ptr< const Submap2D >> &insertion_submaps) REQUIRES(mutex_)
void RunFinalOptimization() override
MapById< SubmapId, SubmapPose > GetAllSubmapPoses() const EXCLUDES(mutex_) override
void AddFixedFramePoseData(int trajectory_id, const sensor::FixedFramePoseData &fixed_frame_pose_data) override EXCLUDES(mutex_)
bool IsTrajectoryFrozen(int trajectory_id) const override REQUIRES(mutex_)
sensor::MapByTime< sensor::ImuData > GetImuData() const override EXCLUDES(mutex_)
MapById< SubmapId, PoseGraphInterface::SubmapData > GetAllSubmapData() const EXCLUDES(mutex_) override
MapById< NodeId, TrajectoryNode > GetTrajectoryNodes() const override EXCLUDES(mutex_)
transform::Rigid3d GetInterpolatedGlobalTrajectoryPose(int trajectory_id, const common::Time time) const REQUIRES(mutex_)
void SetTrajectoryDataFromProto(const proto::TrajectoryData &data) override
void ComputeConstraintsForNode(const NodeId &node_id, std::vector< std::shared_ptr< const Submap2D >> insertion_submaps, bool newly_finished_submap) REQUIRES(mutex_)
void ComputeConstraintsForOldNodes(const SubmapId &submap_id) REQUIRES(mutex_)
void AddSubmapFromProto(const transform::Rigid3d &global_submap_pose, const proto::Submap &submap) override
void SetGlobalSlamOptimizationCallback(PoseGraphInterface::GlobalSlamOptimizationCallback callback) override
std::map< std::string, PoseGraph::LandmarkNode > GetLandmarkNodes() const override EXCLUDES(mutex_)
void AddTrajectoryIfNeeded(int trajectory_id) REQUIRES(mutex_)
GlobalSlamOptimizationCallback global_slam_optimization_callback_
void AddImuData(int trajectory_id, const sensor::ImuData &imu_data) override EXCLUDES(mutex_)
NodeId AddNode(std::shared_ptr< const TrajectoryNode::Data > constant_data, int trajectory_id, const std::vector< std::shared_ptr< const Submap2D >> &insertion_submaps) EXCLUDES(mutex_)
void DispatchOptimization() REQUIRES(mutex_)
std::vector< std::vector< int > > GetConnectedTrajectories() const override
void RunOptimization() EXCLUDES(mutex_)
std::set< NodeId > node_ids
void AddOdometryData(int trajectory_id, const sensor::OdometryData &odometry_data) override EXCLUDES(mutex_)
void SetInitialTrajectoryPose(int from_trajectory_id, int to_trajectory_id, const transform::Rigid3d &pose, const common::Time time) override EXCLUDES(mutex_)
void UpdateTrajectoryConnectivity(const Constraint &constraint) REQUIRES(mutex_)
void SetLandmarkPose(const std::string &landmark_id, const transform::Rigid3d &global_pose) override EXCLUDES(mutex_)
transform::Rigid3d ComputeLocalToGlobalTransform(const MapById< SubmapId, optimization::SubmapSpec2D > &global_submap_poses, int trajectory_id) const REQUIRES(mutex_)
void AddWorkItem(const std::function< void()> &work_item) REQUIRES(mutex_)
std::map< std::string, transform::Rigid3d > GetLandmarkPoses() const override EXCLUDES(mutex_)
void HandleWorkQueue(const constraints::ConstraintBuilder2D::Result &result) REQUIRES(mutex_)
std::unique_ptr< std::deque< std::function< void()> > > work_queue_ GUARDED_BY(mutex_)
PoseGraphInterface::SubmapData GetSubmapData(const SubmapId &submap_id) const EXCLUDES(mutex_) override
PoseGraph2D & operator=(const PoseGraph2D &)=delete
std::map< int, TrajectoryData > GetTrajectoryData() const override EXCLUDES(mutex_)
void FinishTrajectory(int trajectory_id) override