pose_graph_2d.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_2D_POSE_GRAPH_2D_H_
18 #define CARTOGRAPHER_MAPPING_INTERNAL_2D_POSE_GRAPH_2D_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"
47 
48 namespace cartographer {
49 namespace mapping {
50 
51 // Implements the loop closure method called Sparse Pose Adjustment (SPA) from
52 // Konolige, Kurt, et al. "Efficient sparse pose adjustment for 2d mapping."
53 // Intelligent Robots and Systems (IROS), 2010 IEEE/RSJ International Conference
54 // on (pp. 22--29). IEEE, 2010.
55 //
56 // It is extended for submapping:
57 // Each node has been matched against one or more submaps (adding a constraint
58 // for each match), both poses of nodes and of submaps are to be optimized.
59 // All constraints are between a submap i and a node j.
60 class PoseGraph2D : public PoseGraph {
61  public:
63  const proto::PoseGraphOptions& options,
64  std::unique_ptr<optimization::OptimizationProblem2D> optimization_problem,
65  common::ThreadPool* thread_pool);
66  ~PoseGraph2D() override;
67 
68  PoseGraph2D(const PoseGraph2D&) = delete;
69  PoseGraph2D& operator=(const PoseGraph2D&) = delete;
70 
71  // Adds a new node with 'constant_data'. Its 'constant_data->local_pose' was
72  // determined by scan matching against 'insertion_submaps.front()' and the
73  // node data was inserted into the 'insertion_submaps'. If
74  // 'insertion_submaps.front().finished()' is 'true', data was inserted into
75  // this submap for the last time.
77  std::shared_ptr<const TrajectoryNode::Data> constant_data,
78  int trajectory_id,
79  const std::vector<std::shared_ptr<const Submap2D>>& insertion_submaps)
81 
82  void AddImuData(int trajectory_id, const sensor::ImuData& imu_data) override
84  void AddOdometryData(int trajectory_id,
85  const sensor::OdometryData& odometry_data) override
88  int trajectory_id,
89  const sensor::FixedFramePoseData& fixed_frame_pose_data) override
91  void AddLandmarkData(int trajectory_id,
92  const sensor::LandmarkData& landmark_data) override
94 
95  void FinishTrajectory(int trajectory_id) override;
96  bool IsTrajectoryFinished(int trajectory_id) const override REQUIRES(mutex_);
97  void FreezeTrajectory(int trajectory_id) override;
98  bool IsTrajectoryFrozen(int trajectory_id) const override REQUIRES(mutex_);
99  void AddSubmapFromProto(const transform::Rigid3d& global_submap_pose,
100  const proto::Submap& submap) override;
101  void AddNodeFromProto(const transform::Rigid3d& global_pose,
102  const proto::Node& node) override;
103  void SetTrajectoryDataFromProto(const proto::TrajectoryData& data) override;
104  void AddNodeToSubmap(const NodeId& node_id,
105  const SubmapId& submap_id) override;
107  const std::vector<Constraint>& constraints) override;
108  void AddTrimmer(std::unique_ptr<PoseGraphTrimmer> trimmer) override;
109  void RunFinalOptimization() override;
110  std::vector<std::vector<int>> GetConnectedTrajectories() const override;
112  EXCLUDES(mutex_) override;
114  EXCLUDES(mutex_) override;
116  EXCLUDES(mutex_) override;
117  transform::Rigid3d GetLocalToGlobalTransform(int trajectory_id) const
118  EXCLUDES(mutex_) override;
120  EXCLUDES(mutex_);
122  EXCLUDES(mutex_);
123  std::map<std::string, transform::Rigid3d> GetLandmarkPoses() const override
124  EXCLUDES(mutex_);
125  void SetLandmarkPose(const std::string& landmark_id,
126  const transform::Rigid3d& global_pose) override
127  EXCLUDES(mutex_);
129  EXCLUDES(mutex_);
131  EXCLUDES(mutex_);
133  const override EXCLUDES(mutex_);
134  std::map<std::string /* landmark ID */, PoseGraph::LandmarkNode>
135  GetLandmarkNodes() const override EXCLUDES(mutex_);
136  std::map<int, TrajectoryData> GetTrajectoryData() const override
137  EXCLUDES(mutex_);
138  std::vector<Constraint> constraints() const override EXCLUDES(mutex_);
139  void SetInitialTrajectoryPose(int from_trajectory_id, int to_trajectory_id,
140  const transform::Rigid3d& pose,
141  const common::Time time) override
142  EXCLUDES(mutex_);
146  int trajectory_id, const common::Time time) const REQUIRES(mutex_);
147 
148  private:
149  // The current state of the submap in the background threads. When this
150  // transitions to kFinished, all nodes are tried to match against this submap.
151  // Likewise, all new nodes are matched against submaps which are finished.
152  enum class SubmapState { kActive, kFinished };
154  std::shared_ptr<const Submap2D> submap;
155 
156  // IDs of the nodes that were inserted into this map together with
157  // constraints for them. They are not to be matched again when this submap
158  // becomes 'finished'.
159  std::set<NodeId> node_ids;
160 
162  };
163 
165  const REQUIRES(mutex_);
166 
167  // Handles a new work item.
168  void AddWorkItem(const std::function<void()>& work_item) REQUIRES(mutex_);
169 
170  // Adds connectivity and sampler for a trajectory if it does not exist.
171  void AddTrajectoryIfNeeded(int trajectory_id) REQUIRES(mutex_);
172 
173  // Grows the optimization problem to have an entry for every element of
174  // 'insertion_submaps'. Returns the IDs for the 'insertion_submaps'.
176  int trajectory_id, const common::Time time,
177  const std::vector<std::shared_ptr<const Submap2D>>& insertion_submaps)
178  REQUIRES(mutex_);
179 
180  // Adds constraints for a node, and starts scan matching in the background.
182  const NodeId& node_id,
183  std::vector<std::shared_ptr<const Submap2D>> insertion_submaps,
184  bool newly_finished_submap) REQUIRES(mutex_);
185 
186  // Computes constraints for a node and submap pair.
187  void ComputeConstraint(const NodeId& node_id, const SubmapId& submap_id)
188  REQUIRES(mutex_);
189 
190  // Adds constraints for older nodes whenever a new submap is finished.
191  void ComputeConstraintsForOldNodes(const SubmapId& submap_id)
192  REQUIRES(mutex_);
193 
194  // Runs the optimization, executes the trimmers and processes the work queue.
195  void HandleWorkQueue(const constraints::ConstraintBuilder2D::Result& result)
196  REQUIRES(mutex_);
197 
198  // Waits until we caught up (i.e. nothing is waiting to be scheduled), and
199  // all computations have finished.
200  void WaitForAllComputations() EXCLUDES(mutex_);
201 
202  // Runs the optimization. Callers have to make sure, that there is only one
203  // optimization being run at a time.
204  void RunOptimization() EXCLUDES(mutex_);
205 
206  // Computes the local to global map frame transform based on the given
207  // 'global_submap_poses'.
209  const MapById<SubmapId, optimization::SubmapSpec2D>& global_submap_poses,
210  int trajectory_id) const REQUIRES(mutex_);
211 
212  SubmapData GetSubmapDataUnderLock(const SubmapId& submap_id) const
213  REQUIRES(mutex_);
214 
215  common::Time GetLatestNodeTime(const NodeId& node_id,
216  const SubmapId& submap_id) const
217  REQUIRES(mutex_);
218 
219  // Updates the trajectory connectivity structure with a new constraint.
220  void UpdateTrajectoryConnectivity(const Constraint& constraint)
221  REQUIRES(mutex_);
222 
223  const proto::PoseGraphOptions options_;
225  mutable common::Mutex mutex_;
226 
227  // If it exists, further work items must be added to this queue, and will be
228  // considered later.
229  std::unique_ptr<std::deque<std::function<void()>>> work_queue_
230  GUARDED_BY(mutex_);
231 
232  // How our various trajectories are related.
234 
235  // We globally localize a fraction of the nodes from each trajectory.
236  std::unordered_map<int, std::unique_ptr<common::FixedRatioSampler>>
237  global_localization_samplers_ GUARDED_BY(mutex_);
238 
239  // Number of nodes added since last loop closure.
240  int num_nodes_since_last_loop_closure_ GUARDED_BY(mutex_) = 0;
241 
242  // Whether the optimization has to be run before more data is added.
243  bool run_loop_closure_ GUARDED_BY(mutex_) = false;
244 
245  // Schedules optimization (i.e. loop closure) to run.
246  void DispatchOptimization() REQUIRES(mutex_);
247 
248  // Current optimization problem.
249  std::unique_ptr<optimization::OptimizationProblem2D> optimization_problem_;
250  constraints::ConstraintBuilder2D constraint_builder_ GUARDED_BY(mutex_);
251  std::vector<Constraint> constraints_ GUARDED_BY(mutex_);
252 
253  // Submaps get assigned an ID and state as soon as they are seen, even
254  // before they take part in the background computations.
255  MapById<SubmapId, InternalSubmapData> submap_data_ GUARDED_BY(mutex_);
256 
257  // Data that are currently being shown.
258  MapById<NodeId, TrajectoryNode> trajectory_nodes_ GUARDED_BY(mutex_);
259  int num_trajectory_nodes_ GUARDED_BY(mutex_) = 0;
260 
261  // Global submap poses currently used for displaying data.
262  MapById<SubmapId, optimization::SubmapSpec2D> global_submap_poses_
263  GUARDED_BY(mutex_);
264 
265  // Global landmark poses with all observations.
266  std::map<std::string /* landmark ID */, PoseGraph::LandmarkNode>
267  landmark_nodes_ GUARDED_BY(mutex_);
268 
269  // List of all trimmers to consult when optimizations finish.
270  std::vector<std::unique_ptr<PoseGraphTrimmer>> trimmers_ GUARDED_BY(mutex_);
271 
272  // Set of all frozen trajectories not being optimized.
273  std::set<int> frozen_trajectories_ GUARDED_BY(mutex_);
274 
275  // Set of all finished trajectories.
276  std::set<int> finished_trajectories_ GUARDED_BY(mutex_);
277 
278  // Set of all initial trajectory poses.
279  std::map<int, InitialTrajectoryPose> initial_trajectory_poses_
280  GUARDED_BY(mutex_);
281 
282  // Allows querying and manipulating the pose graph by the 'trimmers_'. The
283  // 'mutex_' of the pose graph is held while this class is used.
284  class TrimmingHandle : public Trimmable {
285  public:
286  TrimmingHandle(PoseGraph2D* parent);
287  ~TrimmingHandle() override {}
288 
289  int num_submaps(int trajectory_id) const override;
290  std::vector<SubmapId> GetSubmapIds(int trajectory_id) const override;
291  MapById<SubmapId, SubmapData> GetOptimizedSubmapData() const override
292  REQUIRES(parent_->mutex_);
294  REQUIRES(parent_->mutex_);
295  const std::vector<Constraint>& GetConstraints() const override
296  REQUIRES(parent_->mutex_);
297  void MarkSubmapAsTrimmed(const SubmapId& submap_id)
298  REQUIRES(parent_->mutex_) override;
299  bool IsFinished(int trajectory_id) const override REQUIRES(parent_->mutex_);
300 
301  private:
303  };
304 };
305 
306 } // namespace mapping
307 } // namespace cartographer
308 
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
Rigid3< double > Rigid3d
std::unique_ptr< ConstraintBuilder2D > constraint_builder_
#define EXCLUDES(...)
Definition: mutex.h:53
void AddNodeFromProto(const transform::Rigid3d &global_pose, const proto::Node &node) override
void AddTrimmer(std::unique_ptr< PoseGraphTrimmer > trimmer) 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
Definition: time.h:44
sensor::MapByTime< sensor::OdometryData > GetOdometryData() const override EXCLUDES(mutex_)
void WaitForAllComputations() EXCLUDES(mutex_)
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_)
static time_point time
std::vector< SubmapId > InitializeGlobalSubmapPoses(int trajectory_id, const common::Time time, const std::vector< std::shared_ptr< const Submap2D >> &insertion_submaps) REQUIRES(mutex_)
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_)
#define REQUIRES(...)
Definition: mutex.h:44
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_)
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_)
transform::Rigid3d pose
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


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