constraint_builder_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_CONSTRAINTS_CONSTRAINT_BUILDER_3D_H_
18 #define CARTOGRAPHER_MAPPING_INTERNAL_CONSTRAINTS_CONSTRAINT_BUILDER_3D_H_
19 
20 #include <array>
21 #include <deque>
22 #include <functional>
23 #include <limits>
24 #include <vector>
25 
26 #include "Eigen/Core"
27 #include "Eigen/Geometry"
39 #include "cartographer/mapping/proto/pose_graph/constraint_builder_options.pb.h"
45 
46 namespace cartographer {
47 namespace mapping {
48 namespace constraints {
49 
50 // Asynchronously computes constraints.
51 //
52 // Intermingle an arbitrary number of calls to 'MaybeAddConstraint',
53 // 'MaybeAddGlobalConstraint', and 'NotifyEndOfNode', then call 'WhenDone' once.
54 // After all computations are done the 'callback' will be called with the result
55 // and another MaybeAdd(Global)Constraint()/WhenDone() cycle can follow.
56 //
57 // This class is thread-safe.
59  public:
61  using Result = std::vector<Constraint>;
62 
63  ConstraintBuilder3D(const proto::ConstraintBuilderOptions& options,
64  common::ThreadPoolInterface* thread_pool);
66 
69 
70  // Schedules exploring a new constraint between 'submap' identified by
71  // 'submap_id', and the 'compressed_point_cloud' for 'node_id'.
72  //
73  // 'global_node_pose' and 'global_submap_pose' are initial estimates of poses
74  // in the global map frame, i.e. both are gravity aligned.
75  //
76  // The pointees of 'submap' and 'compressed_point_cloud' must stay valid until
77  // all computations are finished.
78  void MaybeAddConstraint(const SubmapId& submap_id, const Submap3D* submap,
79  const NodeId& node_id,
80  const TrajectoryNode::Data* const constant_data,
81  const std::vector<TrajectoryNode>& submap_nodes,
82  const transform::Rigid3d& global_node_pose,
83  const transform::Rigid3d& global_submap_pose);
84 
85  // Schedules exploring a new constraint between 'submap' identified by
86  // 'submap_id' and the 'compressed_point_cloud' for 'node_id'.
87  // This performs full-submap matching.
88  //
89  // 'global_node_rotation' and 'global_submap_rotation' are initial estimates
90  // of roll and pitch, i.e. their yaw is essentially ignored.
91  //
92  // The pointees of 'submap' and 'compressed_point_cloud' must stay valid until
93  // all computations are finished.
95  const SubmapId& submap_id, const Submap3D* submap, const NodeId& node_id,
96  const TrajectoryNode::Data* const constant_data,
97  const std::vector<TrajectoryNode>& submap_nodes,
98  const Eigen::Quaterniond& global_node_rotation,
99  const Eigen::Quaterniond& global_submap_rotation);
100 
101  // Must be called after all computations related to one node have been added.
102  void NotifyEndOfNode();
103 
104  // Registers the 'callback' to be called with the results, after all
105  // computations triggered by 'MaybeAdd*Constraint' have finished.
106  // 'callback' is executed in the 'ThreadPool'.
107  void WhenDone(const std::function<void(const Result&)>& callback);
108 
109  // Returns the number of consecutive finished nodes.
110  int GetNumFinishedNodes();
111 
112  // Delete data related to 'submap_id'.
113  void DeleteScanMatcher(const SubmapId& submap_id);
114 
115  static void RegisterMetrics(metrics::FamilyFactory* family_factory);
116 
117  private:
121  std::unique_ptr<scan_matching::FastCorrelativeScanMatcher3D>
123  std::weak_ptr<common::Task> creation_task_handle;
124  };
125 
126  // The returned 'grid' and 'fast_correlative_scan_matcher' must only be
127  // accessed after 'creation_task_handle' has completed.
129  const SubmapId& submap_id,
130  const std::vector<TrajectoryNode>& submap_nodes, const Submap3D* submap)
131  REQUIRES(mutex_);
132 
133  // Runs in a background thread and does computations for an additional
134  // constraint.
135  // As output, it may create a new Constraint in 'constraint'.
136  void ComputeConstraint(const SubmapId& submap_id, const NodeId& node_id,
137  bool match_full_submap,
138  const TrajectoryNode::Data* const constant_data,
139  const transform::Rigid3d& global_node_pose,
140  const transform::Rigid3d& global_submap_pose,
141  const SubmapScanMatcher& submap_scan_matcher,
142  std::unique_ptr<Constraint>* constraint)
143  EXCLUDES(mutex_);
144 
146 
147  const proto::ConstraintBuilderOptions options_;
148  common::ThreadPoolInterface* thread_pool_;
149  common::Mutex mutex_;
150 
151  // 'callback' set by WhenDone().
152  std::unique_ptr<std::function<void(const Result&)>> when_done_
153  GUARDED_BY(mutex_);
154 
155  // TODO(gaschler): Use atomics instead of mutex to access these counters.
156  // Number of the node in reaction to which computations are currently
157  // added. This is always the number of nodes seen so far, even when older
158  // nodes are matched against a new submap.
159  int num_started_nodes_ GUARDED_BY(mutex_) = 0;
160 
161  int num_finished_nodes_ GUARDED_BY(mutex_) = 0;
162 
163  std::unique_ptr<common::Task> finish_node_task_ GUARDED_BY(mutex_);
164 
165  std::unique_ptr<common::Task> when_done_task_ GUARDED_BY(mutex_);
166 
167  // Constraints currently being computed in the background. A deque is used to
168  // keep pointers valid when adding more entries. Constraint search results
169  // with below-threshold scores are also 'nullptr'.
170  std::deque<std::unique_ptr<Constraint>> constraints_ GUARDED_BY(mutex_);
171 
172  // Map of dispatched or constructed scan matchers by 'submap_id'.
173  std::map<SubmapId, SubmapScanMatcher> submap_scan_matchers_
174  GUARDED_BY(mutex_);
175 
176  common::FixedRatioSampler sampler_;
177  scan_matching::CeresScanMatcher3D ceres_scan_matcher_;
178 
179  // Histograms of scan matcher scores.
180  common::Histogram score_histogram_ GUARDED_BY(mutex_);
181  common::Histogram rotational_score_histogram_ GUARDED_BY(mutex_);
182  common::Histogram low_resolution_score_histogram_ GUARDED_BY(mutex_);
183 };
184 
185 } // namespace constraints
186 } // namespace mapping
187 } // namespace cartographer
188 
189 #endif // CARTOGRAPHER_MAPPING_INTERNAL_CONSTRAINTS_CONSTRAINT_BUILDER_3D_H_
static void RegisterMetrics(metrics::FamilyFactory *family_factory)
#define EXCLUDES(...)
Definition: mutex.h:53
std::unique_ptr< scan_matching::FastCorrelativeScanMatcher3D > fast_correlative_scan_matcher
ConstraintBuilder3D & operator=(const ConstraintBuilder3D &)=delete
void WhenDone(const std::function< void(const Result &)> &callback)
#define REQUIRES(...)
Definition: mutex.h:44
const SubmapScanMatcher * DispatchScanMatcherConstruction(const SubmapId &submap_id, const std::vector< TrajectoryNode > &submap_nodes, const Submap3D *submap) REQUIRES(mutex_)
void MaybeAddGlobalConstraint(const SubmapId &submap_id, const Submap3D *submap, const NodeId &node_id, const TrajectoryNode::Data *const constant_data, const std::vector< TrajectoryNode > &submap_nodes, const Eigen::Quaterniond &global_node_rotation, const Eigen::Quaterniond &global_submap_rotation)
void MaybeAddConstraint(const SubmapId &submap_id, const Submap3D *submap, const NodeId &node_id, const TrajectoryNode::Data *const constant_data, const std::vector< TrajectoryNode > &submap_nodes, const transform::Rigid3d &global_node_pose, const transform::Rigid3d &global_submap_pose)
void ComputeConstraint(const SubmapId &submap_id, const NodeId &node_id, bool match_full_submap, const TrajectoryNode::Data *const constant_data, const transform::Rigid3d &global_node_pose, const transform::Rigid3d &global_submap_pose, const SubmapScanMatcher &submap_scan_matcher, std::unique_ptr< Constraint > *constraint) EXCLUDES(mutex_)
std::unique_ptr< std::function< void(const Result &)> > when_done_ GUARDED_BY(mutex_)
ConstraintBuilder3D(const proto::ConstraintBuilderOptions &options, common::ThreadPoolInterface *thread_pool)


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