constraint_builder_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_CONSTRAINTS_CONSTRAINT_BUILDER_2D_H_
18 #define CARTOGRAPHER_MAPPING_INTERNAL_CONSTRAINTS_CONSTRAINT_BUILDER_2D_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"
38 #include "cartographer/mapping/proto/pose_graph/constraint_builder_options.pb.h"
42 
43 namespace cartographer {
44 namespace mapping {
45 namespace constraints {
46 
47 // Returns (map <- submap) where 'submap' is a coordinate system at the origin
48 // of the Submap.
49 transform::Rigid2d ComputeSubmapPose(const Submap2D& submap);
50 
51 // Asynchronously computes constraints.
52 //
53 // Intermingle an arbitrary number of calls to 'MaybeAddConstraint',
54 // 'MaybeAddGlobalConstraint', and 'NotifyEndOfNode', then call 'WhenDone' once.
55 // After all computations are done the 'callback' will be called with the result
56 // and another MaybeAdd(Global)Constraint()/WhenDone() cycle can follow.
57 //
58 // This class is thread-safe.
60  public:
62  using Result = std::vector<Constraint>;
63 
64  ConstraintBuilder2D(const proto::ConstraintBuilderOptions& options,
65  common::ThreadPoolInterface* thread_pool);
67 
70 
71  // Schedules exploring a new constraint between 'submap' identified by
72  // 'submap_id', and the 'compressed_point_cloud' for 'node_id'. The
73  // 'initial_relative_pose' is relative to the 'submap'.
74  //
75  // The pointees of 'submap' and 'compressed_point_cloud' must stay valid until
76  // all computations are finished.
77  void MaybeAddConstraint(const SubmapId& submap_id, const Submap2D* submap,
78  const NodeId& node_id,
79  const TrajectoryNode::Data* const constant_data,
80  const transform::Rigid2d& initial_relative_pose);
81 
82  // Schedules exploring a new constraint between 'submap' identified by
83  // 'submap_id' and the 'compressed_point_cloud' for 'node_id'.
84  // This performs full-submap matching.
85  //
86  // The pointees of 'submap' and 'compressed_point_cloud' must stay valid until
87  // all computations are finished.
89  const SubmapId& submap_id, const Submap2D* submap, const NodeId& node_id,
90  const TrajectoryNode::Data* const constant_data);
91 
92  // Must be called after all computations related to one node have been added.
93  void NotifyEndOfNode();
94 
95  // Registers the 'callback' to be called with the results, after all
96  // computations triggered by 'MaybeAdd*Constraint' have finished.
97  // 'callback' is executed in the 'ThreadPool'.
98  void WhenDone(const std::function<void(const Result&)>& callback);
99 
100  // Returns the number of consecutive finished nodes.
101  int GetNumFinishedNodes();
102 
103  // Delete data related to 'submap_id'.
104  void DeleteScanMatcher(const SubmapId& submap_id);
105 
106  static void RegisterMetrics(metrics::FamilyFactory* family_factory);
107 
108  private:
110  const Grid2D* grid;
111  std::unique_ptr<scan_matching::FastCorrelativeScanMatcher2D>
113  std::weak_ptr<common::Task> creation_task_handle;
114  };
115 
116  // The returned 'grid' and 'fast_correlative_scan_matcher' must only be
117  // accessed after 'creation_task_handle' has completed.
119  const SubmapId& submap_id, const Grid2D* grid) REQUIRES(mutex_);
120 
121  // Runs in a background thread and does computations for an additional
122  // constraint, assuming 'submap' and 'compressed_point_cloud' do not change
123  // anymore. As output, it may create a new Constraint in 'constraint'.
124  void ComputeConstraint(const SubmapId& submap_id, const Submap2D* submap,
125  const NodeId& node_id, bool match_full_submap,
126  const TrajectoryNode::Data* const constant_data,
127  const transform::Rigid2d& initial_relative_pose,
128  const SubmapScanMatcher& submap_scan_matcher,
129  std::unique_ptr<Constraint>* constraint)
130  EXCLUDES(mutex_);
131 
133 
134  const constraints::proto::ConstraintBuilderOptions options_;
135  common::ThreadPoolInterface* thread_pool_;
136  common::Mutex mutex_;
137 
138  // 'callback' set by WhenDone().
139  std::unique_ptr<std::function<void(const Result&)>> when_done_
140  GUARDED_BY(mutex_);
141 
142  // TODO(gaschler): Use atomics instead of mutex to access these counters.
143  // Number of the node in reaction to which computations are currently
144  // added. This is always the number of nodes seen so far, even when older
145  // nodes are matched against a new submap.
146  int num_started_nodes_ GUARDED_BY(mutex_) = 0;
147 
148  int num_finished_nodes_ GUARDED_BY(mutex_) = 0;
149 
150  std::unique_ptr<common::Task> finish_node_task_ GUARDED_BY(mutex_);
151 
152  std::unique_ptr<common::Task> when_done_task_ GUARDED_BY(mutex_);
153 
154  // Constraints currently being computed in the background. A deque is used to
155  // keep pointers valid when adding more entries. Constraint search results
156  // with below-threshold scores are also 'nullptr'.
157  std::deque<std::unique_ptr<Constraint>> constraints_ GUARDED_BY(mutex_);
158 
159  // Map of dispatched or constructed scan matchers by 'submap_id'.
160  std::map<SubmapId, SubmapScanMatcher> submap_scan_matchers_
161  GUARDED_BY(mutex_);
162 
163  common::FixedRatioSampler sampler_;
164  scan_matching::CeresScanMatcher2D ceres_scan_matcher_;
165 
166  // Histogram of scan matcher scores.
167  common::Histogram score_histogram_ GUARDED_BY(mutex_);
168 };
169 
170 } // namespace constraints
171 } // namespace mapping
172 } // namespace cartographer
173 
174 #endif // CARTOGRAPHER_MAPPING_INTERNAL_CONSTRAINTS_CONSTRAINT_BUILDER_2D_H_
const SubmapScanMatcher * DispatchScanMatcherConstruction(const SubmapId &submap_id, const Grid2D *grid) REQUIRES(mutex_)
std::unique_ptr< scan_matching::FastCorrelativeScanMatcher2D > fast_correlative_scan_matcher
#define EXCLUDES(...)
Definition: mutex.h:53
static void RegisterMetrics(metrics::FamilyFactory *family_factory)
const constraints::proto::ConstraintBuilderOptions options_
Rigid2< double > Rigid2d
ConstraintBuilder2D & operator=(const ConstraintBuilder2D &)=delete
transform::Rigid2d ComputeSubmapPose(const Submap2D &submap)
#define REQUIRES(...)
Definition: mutex.h:44
void MaybeAddConstraint(const SubmapId &submap_id, const Submap2D *submap, const NodeId &node_id, const TrajectoryNode::Data *const constant_data, const transform::Rigid2d &initial_relative_pose)
ConstraintBuilder2D(const proto::ConstraintBuilderOptions &options, common::ThreadPoolInterface *thread_pool)
void MaybeAddGlobalConstraint(const SubmapId &submap_id, const Submap2D *submap, const NodeId &node_id, const TrajectoryNode::Data *const constant_data)
void ComputeConstraint(const SubmapId &submap_id, const Submap2D *submap, const NodeId &node_id, bool match_full_submap, const TrajectoryNode::Data *const constant_data, const transform::Rigid2d &initial_relative_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_)
void WhenDone(const std::function< void(const Result &)> &callback)


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