constraint_builder_2d.cc
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 
18 
19 #include <cmath>
20 #include <functional>
21 #include <iomanip>
22 #include <iostream>
23 #include <limits>
24 #include <memory>
25 #include <sstream>
26 #include <string>
27 
28 #include "Eigen/Eigenvalues"
32 #include "cartographer/mapping/proto/scan_matching//ceres_scan_matcher_options_2d.pb.h"
33 #include "cartographer/mapping/proto/scan_matching//fast_correlative_scan_matcher_options_2d.pb.h"
38 #include "glog/logging.h"
39 
40 namespace cartographer {
41 namespace mapping {
42 namespace constraints {
43 
51 
53  return transform::Project2D(submap.local_pose());
54 }
55 
57  const constraints::proto::ConstraintBuilderOptions& options,
58  common::ThreadPoolInterface* const thread_pool)
59  : options_(options),
60  thread_pool_(thread_pool),
61  finish_node_task_(common::make_unique<common::Task>()),
62  when_done_task_(common::make_unique<common::Task>()),
63  sampler_(options.sampling_ratio()),
64  ceres_scan_matcher_(options.ceres_scan_matcher_options()) {}
65 
67  common::MutexLocker locker(&mutex_);
68  CHECK_EQ(finish_node_task_->GetState(), common::Task::NEW);
69  CHECK_EQ(when_done_task_->GetState(), common::Task::NEW);
70  CHECK_EQ(constraints_.size(), 0) << "WhenDone() was not called";
71  CHECK_EQ(num_started_nodes_, num_finished_nodes_);
72  CHECK(when_done_ == nullptr);
73 }
74 
76  const SubmapId& submap_id, const Submap2D* const submap,
77  const NodeId& node_id, const TrajectoryNode::Data* const constant_data,
78  const transform::Rigid2d& initial_relative_pose) {
79  if (initial_relative_pose.translation().norm() >
80  options_.max_constraint_distance()) {
81  return;
82  }
83  if (!sampler_.Pulse()) return;
84 
85  common::MutexLocker locker(&mutex_);
86  if (when_done_) {
87  LOG(WARNING)
88  << "MaybeAddConstraint was called while WhenDone was scheduled.";
89  }
90  constraints_.emplace_back();
91  kQueueLengthMetric->Set(constraints_.size());
92  auto* const constraint = &constraints_.back();
93  const auto* scan_matcher =
94  DispatchScanMatcherConstruction(submap_id, submap->grid());
95  auto constraint_task = common::make_unique<common::Task>();
96  constraint_task->SetWorkItem([=]() EXCLUDES(mutex_) {
97  ComputeConstraint(submap_id, submap, node_id, false, /* match_full_submap */
98  constant_data, initial_relative_pose, *scan_matcher,
99  constraint);
100  });
101  constraint_task->AddDependency(scan_matcher->creation_task_handle);
102  auto constraint_task_handle =
103  thread_pool_->Schedule(std::move(constraint_task));
104  finish_node_task_->AddDependency(constraint_task_handle);
105 }
106 
108  const SubmapId& submap_id, const Submap2D* const submap,
109  const NodeId& node_id, const TrajectoryNode::Data* const constant_data) {
110  common::MutexLocker locker(&mutex_);
111  if (when_done_) {
112  LOG(WARNING)
113  << "MaybeAddGlobalConstraint was called while WhenDone was scheduled.";
114  }
115  constraints_.emplace_back();
116  kQueueLengthMetric->Set(constraints_.size());
117  auto* const constraint = &constraints_.back();
118  const auto* scan_matcher =
119  DispatchScanMatcherConstruction(submap_id, submap->grid());
120  auto constraint_task = common::make_unique<common::Task>();
121  constraint_task->SetWorkItem([=]() EXCLUDES(mutex_) {
122  ComputeConstraint(submap_id, submap, node_id, true, /* match_full_submap */
123  constant_data, transform::Rigid2d::Identity(),
124  *scan_matcher, constraint);
125  });
126  constraint_task->AddDependency(scan_matcher->creation_task_handle);
127  auto constraint_task_handle =
128  thread_pool_->Schedule(std::move(constraint_task));
129  finish_node_task_->AddDependency(constraint_task_handle);
130 }
131 
133  common::MutexLocker locker(&mutex_);
134  CHECK(finish_node_task_ != nullptr);
135  finish_node_task_->SetWorkItem([this] {
136  common::MutexLocker locker(&mutex_);
137  ++num_finished_nodes_;
138  });
139  auto finish_node_task_handle =
140  thread_pool_->Schedule(std::move(finish_node_task_));
141  finish_node_task_ = common::make_unique<common::Task>();
142  when_done_task_->AddDependency(finish_node_task_handle);
143  ++num_started_nodes_;
144 }
145 
147  const std::function<void(const ConstraintBuilder2D::Result&)>& callback) {
148  common::MutexLocker locker(&mutex_);
149  CHECK(when_done_ == nullptr);
150  // TODO(gaschler): Consider using just std::function, it can also be empty.
151  when_done_ =
152  common::make_unique<std::function<void(const Result&)>>(callback);
153  CHECK(when_done_task_ != nullptr);
154  when_done_task_->SetWorkItem([this] { RunWhenDoneCallback(); });
155  thread_pool_->Schedule(std::move(when_done_task_));
156  when_done_task_ = common::make_unique<common::Task>();
157 }
158 
161  const Grid2D* const grid) {
162  if (submap_scan_matchers_.count(submap_id) != 0) {
163  return &submap_scan_matchers_.at(submap_id);
164  }
165  auto& submap_scan_matcher = submap_scan_matchers_[submap_id];
166  submap_scan_matcher.grid = grid;
167  auto& scan_matcher_options = options_.fast_correlative_scan_matcher_options();
168  auto scan_matcher_task = common::make_unique<common::Task>();
169  scan_matcher_task->SetWorkItem(
170  [&submap_scan_matcher, &scan_matcher_options]() {
171  submap_scan_matcher.fast_correlative_scan_matcher =
172  common::make_unique<scan_matching::FastCorrelativeScanMatcher2D>(
173  *submap_scan_matcher.grid, scan_matcher_options);
174  });
175  submap_scan_matcher.creation_task_handle =
176  thread_pool_->Schedule(std::move(scan_matcher_task));
177  return &submap_scan_matchers_.at(submap_id);
178 }
179 
181  const SubmapId& submap_id, const Submap2D* const submap,
182  const NodeId& node_id, bool match_full_submap,
183  const TrajectoryNode::Data* const constant_data,
184  const transform::Rigid2d& initial_relative_pose,
185  const SubmapScanMatcher& submap_scan_matcher,
186  std::unique_ptr<ConstraintBuilder2D::Constraint>* constraint) {
187  const transform::Rigid2d initial_pose =
188  ComputeSubmapPose(*submap) * initial_relative_pose;
189 
190  // The 'constraint_transform' (submap i <- node j) is computed from:
191  // - a 'filtered_gravity_aligned_point_cloud' in node j,
192  // - the initial guess 'initial_pose' for (map <- node j),
193  // - the result 'pose_estimate' of Match() (map <- node j).
194  // - the ComputeSubmapPose() (map <- submap i)
195  float score = 0.;
197 
198  // Compute 'pose_estimate' in three stages:
199  // 1. Fast estimate using the fast correlative scan matcher.
200  // 2. Prune if the score is too low.
201  // 3. Refine.
202  if (match_full_submap) {
204  if (submap_scan_matcher.fast_correlative_scan_matcher->MatchFullSubmap(
206  options_.global_localization_min_score(), &score, &pose_estimate)) {
207  CHECK_GT(score, options_.global_localization_min_score());
208  CHECK_GE(node_id.trajectory_id, 0);
209  CHECK_GE(submap_id.trajectory_id, 0);
210  kGlobalConstraintsFoundMetric->Increment();
211  kGlobalConstraintScoresMetric->Observe(score);
212  } else {
213  return;
214  }
215  } else {
216  kConstraintsSearchedMetric->Increment();
217  if (submap_scan_matcher.fast_correlative_scan_matcher->Match(
218  initial_pose, constant_data->filtered_gravity_aligned_point_cloud,
219  options_.min_score(), &score, &pose_estimate)) {
220  // We've reported a successful local match.
221  CHECK_GT(score, options_.min_score());
222  kConstraintsFoundMetric->Increment();
223  kConstraintScoresMetric->Observe(score);
224  } else {
225  return;
226  }
227  }
228  {
229  common::MutexLocker locker(&mutex_);
230  score_histogram_.Add(score);
231  }
232 
233  // Use the CSM estimate as both the initial and previous pose. This has the
234  // effect that, in the absence of better information, we prefer the original
235  // CSM estimate.
236  ceres::Solver::Summary unused_summary;
237  ceres_scan_matcher_.Match(pose_estimate.translation(), pose_estimate,
239  *submap_scan_matcher.grid, &pose_estimate,
240  &unused_summary);
241 
242  const transform::Rigid2d constraint_transform =
243  ComputeSubmapPose(*submap).inverse() * pose_estimate;
244  constraint->reset(new Constraint{submap_id,
245  node_id,
246  {transform::Embed3D(constraint_transform),
247  options_.loop_closure_translation_weight(),
248  options_.loop_closure_rotation_weight()},
250 
251  if (options_.log_matches()) {
252  std::ostringstream info;
253  info << "Node " << node_id << " with "
254  << constant_data->filtered_gravity_aligned_point_cloud.size()
255  << " points on submap " << submap_id << std::fixed;
256  if (match_full_submap) {
257  info << " matches";
258  } else {
259  const transform::Rigid2d difference =
260  initial_pose.inverse() * pose_estimate;
261  info << " differs by translation " << std::setprecision(2)
262  << difference.translation().norm() << " rotation "
263  << std::setprecision(3) << std::abs(difference.normalized_angle());
264  }
265  info << " with score " << std::setprecision(1) << 100. * score << "%.";
266  LOG(INFO) << info.str();
267  }
268 }
269 
271  Result result;
272  std::unique_ptr<std::function<void(const Result&)>> callback;
273  {
274  common::MutexLocker locker(&mutex_);
275  CHECK(when_done_ != nullptr);
276  for (const std::unique_ptr<Constraint>& constraint : constraints_) {
277  if (constraint == nullptr) continue;
278  result.push_back(*constraint);
279  }
280  if (options_.log_matches()) {
281  LOG(INFO) << constraints_.size() << " computations resulted in "
282  << result.size() << " additional constraints.";
283  LOG(INFO) << "Score histogram:\n" << score_histogram_.ToString(10);
284  }
285  constraints_.clear();
286  callback = std::move(when_done_);
287  when_done_.reset();
288  kQueueLengthMetric->Set(constraints_.size());
289  }
290  (*callback)(result);
291 }
292 
294  common::MutexLocker locker(&mutex_);
295  return num_finished_nodes_;
296 }
297 
299  common::MutexLocker locker(&mutex_);
300  if (when_done_) {
301  LOG(WARNING)
302  << "DeleteScanMatcher was called while WhenDone was scheduled.";
303  }
304  submap_scan_matchers_.erase(submap_id);
305 }
306 
308  auto* counts = factory->NewCounterFamily(
309  "mapping_internal_constraints_constraint_builder_2d_constraints",
310  "Constraints computed");
312  counts->Add({{"search_region", "local"}, {"matcher", "searched"}});
314  counts->Add({{"search_region", "local"}, {"matcher", "found"}});
316  counts->Add({{"search_region", "global"}, {"matcher", "searched"}});
318  counts->Add({{"search_region", "global"}, {"matcher", "found"}});
319  auto* queue_length = factory->NewGaugeFamily(
320  "mapping_internal_constraints_constraint_builder_2d_queue_length",
321  "Queue length");
322  kQueueLengthMetric = queue_length->Add({});
323  auto boundaries = metrics::Histogram::FixedWidth(0.05, 20);
324  auto* scores = factory->NewHistogramFamily(
325  "mapping_internal_constraints_constraint_builder_2d_scores",
326  "Constraint scores built", boundaries);
327  kConstraintScoresMetric = scores->Add({{"search_region", "local"}});
328  kGlobalConstraintScoresMetric = scores->Add({{"search_region", "global"}});
329 }
330 
331 } // namespace constraints
332 } // namespace mapping
333 } // namespace cartographer
const SubmapScanMatcher * DispatchScanMatcherConstruction(const SubmapId &submap_id, const Grid2D *grid) REQUIRES(mutex_)
virtual Family< Gauge > * NewGaugeFamily(const std::string &name, const std::string &description)=0
std::unique_ptr< scan_matching::FastCorrelativeScanMatcher2D > fast_correlative_scan_matcher
std::unique_ptr< CeresScanMatcher2D > ceres_scan_matcher_
#define EXCLUDES(...)
Definition: mutex.h:53
static void RegisterMetrics(metrics::FamilyFactory *family_factory)
Rigid3< T > Embed3D(const Rigid2< T > &transform)
Definition: transform.h:110
const constraints::proto::ConstraintBuilderOptions options_
virtual Family< Counter > * NewCounterFamily(const std::string &name, const std::string &description)=0
virtual Family< Histogram > * NewHistogramFamily(const std::string &name, const std::string &description, const Histogram::BucketBoundaries &boundaries)=0
Rigid2< T > Project2D(const Rigid3< T > &transform)
Definition: transform.h:103
static Rigid2< FloatType > Identity()
FakeThreadPool thread_pool_
Definition: task_test.cc:70
proto::ProbabilityGridRangeDataInserterOptions2D options_
transform::Rigid2d ComputeSubmapPose(const Submap2D &submap)
static BucketBoundaries FixedWidth(double width, int num_finite_buckets)
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)
const Grid2D * grid() const
Definition: submap_2d.h:54
transform::Rigid3d local_pose() const
Definition: submaps.h:75
const Vector & translation() const
void MaybeAddGlobalConstraint(const SubmapId &submap_id, const Submap2D *submap, const NodeId &node_id, const TrajectoryNode::Data *const constant_data)
static Counter * Null()
Definition: counter.cc:33
virtual std::weak_ptr< Task > Schedule(std::unique_ptr< Task > task)=0
void Match(const Eigen::Vector2d &target_translation, const transform::Rigid2d &initial_pose_estimate, const sensor::PointCloud &point_cloud, const Grid2D &grid, transform::Rigid2d *pose_estimate, ceres::Solver::Summary *summary) const
Mutex::Locker MutexLocker
Definition: mutex.h:95
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_)
static Gauge * Null()
Definition: gauge.cc:36
void WhenDone(const std::function< void(const Result &)> &callback)


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