pose_graph_3d.h
Go to the documentation of this file.
1 /*
2  * Copyright 2016 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #ifndef CARTOGRAPHER_MAPPING_INTERNAL_3D_POSE_GRAPH_3D_H_
18 #define CARTOGRAPHER_MAPPING_INTERNAL_3D_POSE_GRAPH_3D_H_
19 
20 #include <deque>
21 #include <functional>
22 #include <limits>
23 #include <map>
24 #include <memory>
25 #include <set>
26 #include <unordered_map>
27 #include <vector>
28 
29 #include "Eigen/Core"
30 #include "Eigen/Geometry"
46 
47 namespace cartographer {
48 namespace mapping {
49 
50 // Implements the loop closure method called Sparse Pose Adjustment (SPA) from
51 // Konolige, Kurt, et al. "Efficient sparse pose adjustment for 2d mapping."
52 // Intelligent Robots and Systems (IROS), 2010 IEEE/RSJ International Conference
53 // on (pp. 22--29). IEEE, 2010.
54 //
55 // It is extended for submapping in 3D:
56 // Each node has been matched against one or more submaps (adding a constraint
57 // for each match), both poses of nodes and of submaps are to be optimized.
58 // All constraints are between a submap i and a node j.
59 class PoseGraph3D : public PoseGraph {
60  public:
62  const proto::PoseGraphOptions& options,
63  std::unique_ptr<optimization::OptimizationProblem3D> optimization_problem,
64  common::ThreadPool* thread_pool);
65  ~PoseGraph3D() override;
66 
67  PoseGraph3D(const PoseGraph3D&) = delete;
68  PoseGraph3D& operator=(const PoseGraph3D&) = delete;
69 
70  // Adds a new node with 'constant_data'. Its 'constant_data->local_pose' was
71  // determined by scan matching against 'insertion_submaps.front()' and the
72  // node data was inserted into the 'insertion_submaps'. If
73  // 'insertion_submaps.front().finished()' is 'true', data was inserted into
74  // this submap for the last time.
76  std::shared_ptr<const TrajectoryNode::Data> constant_data,
77  int trajectory_id,
78  const std::vector<std::shared_ptr<const Submap3D>>& insertion_submaps)
80 
81  void AddImuData(int trajectory_id, const sensor::ImuData& imu_data) override
83  void AddOdometryData(int trajectory_id,
84  const sensor::OdometryData& odometry_data) override
87  int trajectory_id,
88  const sensor::FixedFramePoseData& fixed_frame_pose_data) override
90  void AddLandmarkData(int trajectory_id,
91  const sensor::LandmarkData& landmark_data) override
93 
94  void FinishTrajectory(int trajectory_id) override;
95  bool IsTrajectoryFinished(int trajectory_id) const override REQUIRES(mutex_);
96  void FreezeTrajectory(int trajectory_id) override;
97  bool IsTrajectoryFrozen(int trajectory_id) const override REQUIRES(mutex_);
98  void AddSubmapFromProto(const transform::Rigid3d& global_submap_pose,
99  const proto::Submap& submap) override;
100  void AddNodeFromProto(const transform::Rigid3d& global_pose,
101  const proto::Node& node) override;
102  void SetTrajectoryDataFromProto(const proto::TrajectoryData& data) override;
103  void AddNodeToSubmap(const NodeId& node_id,
104  const SubmapId& submap_id) override;
106  const std::vector<Constraint>& constraints) override;
107  void AddTrimmer(std::unique_ptr<PoseGraphTrimmer> trimmer) override;
108  void RunFinalOptimization() override;
109  std::vector<std::vector<int>> GetConnectedTrajectories() const override;
110  PoseGraph::SubmapData GetSubmapData(const SubmapId& submap_id) const
111  EXCLUDES(mutex_) override;
113  EXCLUDES(mutex_) override;
115  EXCLUDES(mutex_) override;
116  transform::Rigid3d GetLocalToGlobalTransform(int trajectory_id) const
117  EXCLUDES(mutex_) override;
119  EXCLUDES(mutex_);
121  EXCLUDES(mutex_);
122  std::map<std::string, transform::Rigid3d> GetLandmarkPoses() const override
123  EXCLUDES(mutex_);
124  void SetLandmarkPose(const std::string& landmark_id,
125  const transform::Rigid3d& global_pose) override
126  EXCLUDES(mutex_);
128  EXCLUDES(mutex_);
130  EXCLUDES(mutex_);
132  const override EXCLUDES(mutex_);
133  std::map<std::string /* landmark ID */, PoseGraph::LandmarkNode>
134  GetLandmarkNodes() const override EXCLUDES(mutex_);
135  std::map<int, TrajectoryData> GetTrajectoryData() const override;
136 
137  std::vector<Constraint> constraints() const override EXCLUDES(mutex_);
138  void SetInitialTrajectoryPose(int from_trajectory_id, int to_trajectory_id,
139  const transform::Rigid3d& pose,
140  const common::Time time) override
141  EXCLUDES(mutex_);
145  int trajectory_id, const common::Time time) const REQUIRES(mutex_);
146 
147  protected:
148  // Waits until we caught up (i.e. nothing is waiting to be scheduled), and
149  // all computations have finished.
151 
152  private:
153  // The current state of the submap in the background threads. When this
154  // transitions to kFinished, all nodes are tried to match against this submap.
155  // Likewise, all new nodes are matched against submaps which are finished.
156  enum class SubmapState { kActive, kFinished };
158  std::shared_ptr<const Submap3D> submap;
159 
160  // IDs of the nodes that were inserted into this map together with
161  // constraints for them. They are not to be matched again when this submap
162  // becomes 'finished'.
163  std::set<NodeId> node_ids;
164 
166  };
167 
169 
170  // Handles a new work item.
171  void AddWorkItem(const std::function<void()>& work_item) REQUIRES(mutex_);
172 
173  // Adds connectivity and sampler for a trajectory if it does not exist.
174  void AddTrajectoryIfNeeded(int trajectory_id) REQUIRES(mutex_);
175 
176  // Grows the optimization problem to have an entry for every element of
177  // 'insertion_submaps'. Returns the IDs for the 'insertion_submaps'.
179  int trajectory_id, const common::Time time,
180  const std::vector<std::shared_ptr<const Submap3D>>& insertion_submaps)
181  REQUIRES(mutex_);
182 
183  // Adds constraints for a node, and starts scan matching in the background.
185  const NodeId& node_id,
186  std::vector<std::shared_ptr<const Submap3D>> insertion_submaps,
187  bool newly_finished_submap) REQUIRES(mutex_);
188 
189  // Computes constraints for a node and submap pair.
190  void ComputeConstraint(const NodeId& node_id, const SubmapId& submap_id)
191  REQUIRES(mutex_);
192 
193  // Adds constraints for older nodes whenever a new submap is finished.
194  void ComputeConstraintsForOldNodes(const SubmapId& submap_id)
195  REQUIRES(mutex_);
196 
197  // Runs the optimization, executes the trimmers and processes the work queue.
198  void HandleWorkQueue(const constraints::ConstraintBuilder3D::Result& result)
199  REQUIRES(mutex_);
200 
201  // Runs the optimization. Callers have to make sure, that there is only one
202  // optimization being run at a time.
203  void RunOptimization() EXCLUDES(mutex_);
204 
205  // Computes the local to global map frame transform based on the given
206  // 'global_submap_poses'.
208  const MapById<SubmapId, optimization::SubmapSpec3D>& global_submap_poses,
209  int trajectory_id) const REQUIRES(mutex_);
210 
211  PoseGraph::SubmapData GetSubmapDataUnderLock(const SubmapId& submap_id) const
212  REQUIRES(mutex_);
213 
214  common::Time GetLatestNodeTime(const NodeId& node_id,
215  const SubmapId& submap_id) const
216  REQUIRES(mutex_);
217 
218  // Logs histograms for the translational and rotational residual of node
219  // poses.
220  void LogResidualHistograms() const REQUIRES(mutex_);
221 
222  // Updates the trajectory connectivity structure with a new constraint.
223  void UpdateTrajectoryConnectivity(const Constraint& constraint)
224  REQUIRES(mutex_);
225 
226  // Schedules optimization (i.e. loop closure) to run.
227  void DispatchOptimization() REQUIRES(mutex_);
228 
229  const proto::PoseGraphOptions options_;
231  mutable common::Mutex mutex_;
232 
233  // If it exists, further work items must be added to this queue, and will be
234  // considered later.
235  std::unique_ptr<std::deque<std::function<void()>>> work_queue_
236  GUARDED_BY(mutex_);
237 
238  // How our various trajectories are related.
240 
241  // We globally localize a fraction of the nodes from each trajectory.
242  std::unordered_map<int, std::unique_ptr<common::FixedRatioSampler>>
243  global_localization_samplers_ GUARDED_BY(mutex_);
244 
245  // Number of nodes added since last loop closure.
246  int num_nodes_since_last_loop_closure_ GUARDED_BY(mutex_) = 0;
247 
248  // Whether the optimization has to be run before more data is added.
249  bool run_loop_closure_ GUARDED_BY(mutex_) = false;
250 
251  // Current optimization problem.
252  std::unique_ptr<optimization::OptimizationProblem3D> optimization_problem_;
253  constraints::ConstraintBuilder3D constraint_builder_ GUARDED_BY(mutex_);
254  std::vector<Constraint> constraints_ GUARDED_BY(mutex_);
255 
256  // Submaps get assigned an ID and state as soon as they are seen, even
257  // before they take part in the background computations.
258  MapById<SubmapId, InternalSubmapData> submap_data_ GUARDED_BY(mutex_);
259 
260  // Data that are currently being shown.
261  MapById<NodeId, TrajectoryNode> trajectory_nodes_ GUARDED_BY(mutex_);
262  int num_trajectory_nodes_ GUARDED_BY(mutex_) = 0;
263 
264  // Global submap poses currently used for displaying data.
265  MapById<SubmapId, optimization::SubmapSpec3D> global_submap_poses_
266  GUARDED_BY(mutex_);
267 
268  // Global landmark poses with all observations.
269  std::map<std::string /* landmark ID */, PoseGraph::LandmarkNode>
270  landmark_nodes_ GUARDED_BY(mutex_);
271 
272  // List of all trimmers to consult when optimizations finish.
273  std::vector<std::unique_ptr<PoseGraphTrimmer>> trimmers_ GUARDED_BY(mutex_);
274 
275  // Set of all frozen trajectories not being optimized.
276  std::set<int> frozen_trajectories_ GUARDED_BY(mutex_);
277 
278  // Set of all finished trajectories.
279  std::set<int> finished_trajectories_ GUARDED_BY(mutex_);
280 
281  // Set of all initial trajectory poses.
282  std::map<int, InitialTrajectoryPose> initial_trajectory_poses_
283  GUARDED_BY(mutex_);
284 
285  // Allows querying and manipulating the pose graph by the 'trimmers_'. The
286  // 'mutex_' of the pose graph is held while this class is used.
287  class TrimmingHandle : public Trimmable {
288  public:
289  TrimmingHandle(PoseGraph3D* parent);
290  ~TrimmingHandle() override {}
291 
292  int num_submaps(int trajectory_id) const override;
293  std::vector<SubmapId> GetSubmapIds(int trajectory_id) const override;
294  MapById<SubmapId, SubmapData> GetOptimizedSubmapData() const override
295  REQUIRES(parent_->mutex_);
297  REQUIRES(parent_->mutex_);
298  const std::vector<Constraint>& GetConstraints() const override
299  REQUIRES(parent_->mutex_);
300  void MarkSubmapAsTrimmed(const SubmapId& submap_id)
301  REQUIRES(parent_->mutex_) override;
302  bool IsFinished(int trajectory_id) const override REQUIRES(parent_->mutex_);
303 
304  private:
306  };
307 };
308 
309 } // namespace mapping
310 } // namespace cartographer
311 
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_)
Rigid3< double > Rigid3d
std::unique_ptr< ConstraintBuilder2D > constraint_builder_
#define EXCLUDES(...)
Definition: mutex.h:53
PoseGraph3D & operator=(const PoseGraph3D &)=delete
void AddWorkItem(const std::function< void()> &work_item) REQUIRES(mutex_)
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
Definition: time.h:44
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_)
static time_point time
#define REQUIRES(...)
Definition: mutex.h:44
void AddSubmapFromProto(const transform::Rigid3d &global_submap_pose, const proto::Submap &submap) 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_)
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
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_)
transform::Rigid3d pose
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
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_


cartographer
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:00:58