17 #ifndef CARTOGRAPHER_MAPPING_INTERNAL_3D_POSE_GRAPH_3D_H_ 18 #define CARTOGRAPHER_MAPPING_INTERNAL_3D_POSE_GRAPH_3D_H_ 26 #include <unordered_map> 30 #include "Eigen/Geometry" 62 const proto::PoseGraphOptions& options,
63 std::unique_ptr<optimization::OptimizationProblem3D> optimization_problem,
76 std::shared_ptr<const TrajectoryNode::Data> constant_data,
78 const std::vector<std::shared_ptr<const Submap3D>>& insertion_submaps)
99 const proto::Submap& submap)
override;
101 const proto::Node& node)
override;
104 const SubmapId& submap_id)
override;
106 const std::vector<Constraint>&
constraints)
override;
107 void AddTrimmer(std::unique_ptr<PoseGraphTrimmer> trimmer)
override;
171 void AddWorkItem(const std::function<
void()>& work_item) REQUIRES(mutex_);
179 int trajectory_id, const common::
Time time,
180 const std::vector<std::shared_ptr<const
Submap3D>>& insertion_submaps)
186 std::vector<std::shared_ptr<const
Submap3D>> insertion_submaps,
187 bool newly_finished_submap) REQUIRES(mutex_);
198 void HandleWorkQueue(const constraints::ConstraintBuilder3D::Result& result)
208 const
MapById<
SubmapId, optimization::SubmapSpec3D>& global_submap_poses,
209 int trajectory_id) const REQUIRES(mutex_);
215 const SubmapId& submap_id) const
231 mutable common::Mutex mutex_;
235 std::unique_ptr<std::deque<std::function<
void()>>> work_queue_
242 std::unordered_map<
int, std::unique_ptr<common::FixedRatioSampler>>
243 global_localization_samplers_
GUARDED_BY(mutex_);
246 int num_nodes_since_last_loop_closure_
GUARDED_BY(mutex_) = 0;
249 bool run_loop_closure_
GUARDED_BY(mutex_) = false;
262 int num_trajectory_nodes_
GUARDED_BY(mutex_) = 0;
265 MapById<SubmapId, optimization::SubmapSpec3D> global_submap_poses_
276 std::set<
int> frozen_trajectories_
GUARDED_BY(mutex_);
279 std::set<
int> finished_trajectories_
GUARDED_BY(mutex_);
292 int num_submaps(
int trajectory_id)
const override;
293 std::vector<SubmapId> GetSubmapIds(
int trajectory_id)
const override;
298 const std::vector<Constraint>& GetConstraints()
const override 300 void MarkSubmapAsTrimmed(
const SubmapId& submap_id)
302 bool IsFinished(
int trajectory_id)
const override REQUIRES(parent_->mutex_);
312 #endif // CARTOGRAPHER_MAPPING_INTERNAL_3D_POSE_GRAPH_3D_H_
MapById< SubmapId, SubmapData > GetSubmapDataUnderLock() const REQUIRES(mutex_)
void WaitForAllComputations() EXCLUDES(mutex_)
void FinishTrajectory(int trajectory_id) override
std::vector< SubmapId > InitializeGlobalSubmapPoses(int trajectory_id, const common::Time time, const std::vector< std::shared_ptr< const Submap3D >> &insertion_submaps) REQUIRES(mutex_)
std::unique_ptr< std::deque< std::function< void()> > > work_queue_ GUARDED_BY(mutex_)
void SetGlobalSlamOptimizationCallback(PoseGraphInterface::GlobalSlamOptimizationCallback callback) override
void AddTrajectoryIfNeeded(int trajectory_id) REQUIRES(mutex_)
std::unique_ptr< ConstraintBuilder2D > constraint_builder_
PoseGraph3D & operator=(const PoseGraph3D &)=delete
void AddWorkItem(const std::function< void()> &work_item) REQUIRES(mutex_)
std::shared_ptr< const Submap3D > submap
transform::Rigid3d GetInterpolatedGlobalTrajectoryPose(int trajectory_id, const common::Time time) const REQUIRES(mutex_)
const proto::PoseGraphOptions options_
sensor::MapByTime< sensor::ImuData > GetImuData() const override EXCLUDES(mutex_)
std::function< void(const std::map< int, SubmapId > &, const std::map< int, NodeId > &)> GlobalSlamOptimizationCallback
void SetInitialTrajectoryPose(int from_trajectory_id, int to_trajectory_id, const transform::Rigid3d &pose, const common::Time time) override EXCLUDES(mutex_)
void AddTrimmer(std::unique_ptr< PoseGraphTrimmer > trimmer) override
UniversalTimeScaleClock::time_point Time
void FreezeTrajectory(int trajectory_id) override
void AddLandmarkData(int trajectory_id, const sensor::LandmarkData &landmark_data) override EXCLUDES(mutex_)
void AddImuData(int trajectory_id, const sensor::ImuData &imu_data) override EXCLUDES(mutex_)
void ComputeConstraintsForOldNodes(const SubmapId &submap_id) REQUIRES(mutex_)
void SetLandmarkPose(const std::string &landmark_id, const transform::Rigid3d &global_pose) override EXCLUDES(mutex_)
void AddSubmapFromProto(const transform::Rigid3d &global_submap_pose, const proto::Submap &submap) override
~TrimmingHandle() override
void AddNodeFromProto(const transform::Rigid3d &global_pose, const proto::Node &node) override
MapById< NodeId, TrajectoryNode > GetTrajectoryNodes() const override EXCLUDES(mutex_)
std::map< std::string, transform::Rigid3d > GetLandmarkPoses() const override EXCLUDES(mutex_)
void HandleWorkQueue(const constraints::ConstraintBuilder3D::Result &result) REQUIRES(mutex_)
std::set< NodeId > node_ids
transform::Rigid3d GetLocalToGlobalTransform(int trajectory_id) const EXCLUDES(mutex_) override
bool IsTrajectoryFrozen(int trajectory_id) const override REQUIRES(mutex_)
void ComputeConstraint(const NodeId &node_id, const SubmapId &submap_id) REQUIRES(mutex_)
std::map< int, TrajectoryData > GetTrajectoryData() const override
void UpdateTrajectoryConnectivity(const Constraint &constraint) REQUIRES(mutex_)
PoseGraph::SubmapData GetSubmapData(const SubmapId &submap_id) const EXCLUDES(mutex_) override
PoseGraph3D *const parent_
void ComputeConstraintsForNode(const NodeId &node_id, std::vector< std::shared_ptr< const Submap3D >> insertion_submaps, bool newly_finished_submap) REQUIRES(mutex_)
void AddSerializedConstraints(const std::vector< Constraint > &constraints) override
NodeId AddNode(std::shared_ptr< const TrajectoryNode::Data > constant_data, int trajectory_id, const std::vector< std::shared_ptr< const Submap3D >> &insertion_submaps) EXCLUDES(mutex_)
sensor::MapByTime< sensor::FixedFramePoseData > GetFixedFramePoseData() const override EXCLUDES(mutex_)
void AddFixedFramePoseData(int trajectory_id, const sensor::FixedFramePoseData &fixed_frame_pose_data) override EXCLUDES(mutex_)
void AddNodeToSubmap(const NodeId &node_id, const SubmapId &submap_id) override
void AddOdometryData(int trajectory_id, const sensor::OdometryData &odometry_data) override EXCLUDES(mutex_)
void DispatchOptimization() REQUIRES(mutex_)
MapById< SubmapId, SubmapData > GetAllSubmapData() const EXCLUDES(mutex_) override
std::unique_ptr< optimization::OptimizationProblem3D > optimization_problem_
void LogResidualHistograms() const REQUIRES(mutex_)
sensor::MapByTime< sensor::OdometryData > GetOdometryData() const override EXCLUDES(mutex_)
PoseGraph3D(const proto::PoseGraphOptions &options, std::unique_ptr< optimization::OptimizationProblem3D > optimization_problem, common::ThreadPool *thread_pool)
void RunOptimization() EXCLUDES(mutex_)
std::vector< Constraint > constraints() const override EXCLUDES(mutex_)
transform::Rigid3d ComputeLocalToGlobalTransform(const MapById< SubmapId, optimization::SubmapSpec3D > &global_submap_poses, int trajectory_id) const REQUIRES(mutex_)
std::map< std::string, PoseGraph::LandmarkNode > GetLandmarkNodes() const override EXCLUDES(mutex_)
std::vector< std::vector< int > > GetConnectedTrajectories() const override
bool IsTrajectoryFinished(int trajectory_id) const override REQUIRES(mutex_)
MapById< NodeId, TrajectoryNodePose > GetTrajectoryNodePoses() const override EXCLUDES(mutex_)
GlobalSlamOptimizationCallback global_slam_optimization_callback_
MapById< SubmapId, SubmapPose > GetAllSubmapPoses() const EXCLUDES(mutex_) override
void RunFinalOptimization() override
common::Time GetLatestNodeTime(const NodeId &node_id, const SubmapId &submap_id) const REQUIRES(mutex_)
void SetTrajectoryDataFromProto(const proto::TrajectoryData &data) override
TrajectoryConnectivityState trajectory_connectivity_state_