constraint_builder_3d.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_3d.pb.h"
33 #include "cartographer/mapping/proto/scan_matching//fast_correlative_scan_matcher_options_3d.pb.h"
38 #include "glog/logging.h"
39 
40 namespace cartographer {
41 namespace mapping {
42 namespace constraints {
43 
57 
59  const proto::ConstraintBuilderOptions& options,
60  common::ThreadPoolInterface* const thread_pool)
61  : options_(options),
62  thread_pool_(thread_pool),
63  finish_node_task_(common::make_unique<common::Task>()),
64  when_done_task_(common::make_unique<common::Task>()),
65  sampler_(options.sampling_ratio()),
66  ceres_scan_matcher_(options.ceres_scan_matcher_options_3d()) {}
67 
69  common::MutexLocker locker(&mutex_);
70  CHECK_EQ(finish_node_task_->GetState(), common::Task::NEW);
71  CHECK_EQ(when_done_task_->GetState(), common::Task::NEW);
72  CHECK_EQ(constraints_.size(), 0) << "WhenDone() was not called";
73  CHECK_EQ(num_started_nodes_, num_finished_nodes_);
74  CHECK(when_done_ == nullptr);
75 }
76 
78  const SubmapId& submap_id, const Submap3D* const submap,
79  const NodeId& node_id, const TrajectoryNode::Data* const constant_data,
80  const std::vector<TrajectoryNode>& submap_nodes,
81  const transform::Rigid3d& global_node_pose,
82  const transform::Rigid3d& global_submap_pose) {
83  if ((global_node_pose.translation() - global_submap_pose.translation())
84  .norm() > options_.max_constraint_distance()) {
85  return;
86  }
87  if (!sampler_.Pulse()) return;
88 
89  common::MutexLocker locker(&mutex_);
90  if (when_done_) {
91  LOG(WARNING)
92  << "MaybeAddConstraint was called while WhenDone was scheduled.";
93  }
94  constraints_.emplace_back();
95  kQueueLengthMetric->Set(constraints_.size());
96  auto* const constraint = &constraints_.back();
97  const auto* scan_matcher =
98  DispatchScanMatcherConstruction(submap_id, submap_nodes, submap);
99  auto constraint_task = common::make_unique<common::Task>();
100  constraint_task->SetWorkItem([=]() EXCLUDES(mutex_) {
101  ComputeConstraint(submap_id, node_id, false, /* match_full_submap */
102  constant_data, global_node_pose, global_submap_pose,
103  *scan_matcher, constraint);
104  });
105  constraint_task->AddDependency(scan_matcher->creation_task_handle);
106  auto constraint_task_handle =
107  thread_pool_->Schedule(std::move(constraint_task));
108  finish_node_task_->AddDependency(constraint_task_handle);
109 }
110 
112  const SubmapId& submap_id, const Submap3D* const submap,
113  const NodeId& node_id, const TrajectoryNode::Data* const constant_data,
114  const std::vector<TrajectoryNode>& submap_nodes,
115  const Eigen::Quaterniond& global_node_rotation,
116  const Eigen::Quaterniond& global_submap_rotation) {
117  common::MutexLocker locker(&mutex_);
118  if (when_done_) {
119  LOG(WARNING)
120  << "MaybeAddGlobalConstraint was called while WhenDone was scheduled.";
121  }
122  constraints_.emplace_back();
123  kQueueLengthMetric->Set(constraints_.size());
124  auto* const constraint = &constraints_.back();
125  const auto* scan_matcher =
126  DispatchScanMatcherConstruction(submap_id, submap_nodes, submap);
127  auto constraint_task = common::make_unique<common::Task>();
128  constraint_task->SetWorkItem([=]() EXCLUDES(mutex_) {
129  ComputeConstraint(submap_id, node_id, true, /* match_full_submap */
130  constant_data,
131  transform::Rigid3d::Rotation(global_node_rotation),
132  transform::Rigid3d::Rotation(global_submap_rotation),
133  *scan_matcher, constraint);
134  });
135  constraint_task->AddDependency(scan_matcher->creation_task_handle);
136  auto constraint_task_handle =
137  thread_pool_->Schedule(std::move(constraint_task));
138  finish_node_task_->AddDependency(constraint_task_handle);
139 }
140 
142  common::MutexLocker locker(&mutex_);
143  CHECK(finish_node_task_ != nullptr);
144  finish_node_task_->SetWorkItem([this] {
145  common::MutexLocker locker(&mutex_);
146  ++num_finished_nodes_;
147  });
148  auto finish_node_task_handle =
149  thread_pool_->Schedule(std::move(finish_node_task_));
150  finish_node_task_ = common::make_unique<common::Task>();
151  when_done_task_->AddDependency(finish_node_task_handle);
152  ++num_started_nodes_;
153 }
154 
156  const std::function<void(const ConstraintBuilder3D::Result&)>& callback) {
157  common::MutexLocker locker(&mutex_);
158  CHECK(when_done_ == nullptr);
159  // TODO(gaschler): Consider using just std::function, it can also be empty.
160  when_done_ =
161  common::make_unique<std::function<void(const Result&)>>(callback);
162  CHECK(when_done_task_ != nullptr);
163  when_done_task_->SetWorkItem([this] { RunWhenDoneCallback(); });
164  thread_pool_->Schedule(std::move(when_done_task_));
165  when_done_task_ = common::make_unique<common::Task>();
166 }
167 
170  const SubmapId& submap_id, const std::vector<TrajectoryNode>& submap_nodes,
171  const Submap3D* submap) {
172  if (submap_scan_matchers_.count(submap_id) != 0) {
173  return &submap_scan_matchers_.at(submap_id);
174  }
175  auto& submap_scan_matcher = submap_scan_matchers_[submap_id];
176  submap_scan_matcher.high_resolution_hybrid_grid =
177  &submap->high_resolution_hybrid_grid();
178  submap_scan_matcher.low_resolution_hybrid_grid =
179  &submap->low_resolution_hybrid_grid();
180  auto& scan_matcher_options =
181  options_.fast_correlative_scan_matcher_options_3d();
182  auto scan_matcher_task = common::make_unique<common::Task>();
183  scan_matcher_task->SetWorkItem(
184  [&submap_scan_matcher, &scan_matcher_options, submap_nodes]() {
185  submap_scan_matcher.fast_correlative_scan_matcher =
186  common::make_unique<scan_matching::FastCorrelativeScanMatcher3D>(
187  *submap_scan_matcher.high_resolution_hybrid_grid,
188  submap_scan_matcher.low_resolution_hybrid_grid, submap_nodes,
189  scan_matcher_options);
190  });
191  submap_scan_matcher.creation_task_handle =
192  thread_pool_->Schedule(std::move(scan_matcher_task));
193  return &submap_scan_matchers_.at(submap_id);
194 }
195 
197  const SubmapId& submap_id, const NodeId& node_id, bool match_full_submap,
198  const TrajectoryNode::Data* const constant_data,
199  const transform::Rigid3d& global_node_pose,
200  const transform::Rigid3d& global_submap_pose,
201  const SubmapScanMatcher& submap_scan_matcher,
202  std::unique_ptr<Constraint>* constraint) {
203  // The 'constraint_transform' (submap i <- node j) is computed from:
204  // - a 'high_resolution_point_cloud' in node j and
205  // - the initial guess 'initial_pose' (submap i <- node j).
206  std::unique_ptr<scan_matching::FastCorrelativeScanMatcher3D::Result>
207  match_result;
208 
209  // Compute 'pose_estimate' in three stages:
210  // 1. Fast estimate using the fast correlative scan matcher.
211  // 2. Prune if the score is too low.
212  // 3. Refine.
213  if (match_full_submap) {
215  match_result =
216  submap_scan_matcher.fast_correlative_scan_matcher->MatchFullSubmap(
217  global_node_pose.rotation(), global_submap_pose.rotation(),
218  *constant_data, options_.global_localization_min_score());
219  if (match_result != nullptr) {
220  CHECK_GT(match_result->score, options_.global_localization_min_score());
221  CHECK_GE(node_id.trajectory_id, 0);
222  CHECK_GE(submap_id.trajectory_id, 0);
223  kGlobalConstraintsFoundMetric->Increment();
224  kGlobalConstraintScoresMetric->Observe(match_result->score);
226  match_result->rotational_score);
228  match_result->low_resolution_score);
229  } else {
230  return;
231  }
232  } else {
233  kConstraintsSearchedMetric->Increment();
234  match_result = submap_scan_matcher.fast_correlative_scan_matcher->Match(
235  global_node_pose, global_submap_pose, *constant_data,
236  options_.min_score());
237  if (match_result != nullptr) {
238  // We've reported a successful local match.
239  CHECK_GT(match_result->score, options_.min_score());
240  kConstraintsFoundMetric->Increment();
241  kConstraintScoresMetric->Observe(match_result->score);
243  match_result->rotational_score);
245  match_result->low_resolution_score);
246  } else {
247  return;
248  }
249  }
250  {
251  common::MutexLocker locker(&mutex_);
252  score_histogram_.Add(match_result->score);
253  rotational_score_histogram_.Add(match_result->rotational_score);
254  low_resolution_score_histogram_.Add(match_result->low_resolution_score);
255  }
256 
257  // Use the CSM estimate as both the initial and previous pose. This has the
258  // effect that, in the absence of better information, we prefer the original
259  // CSM estimate.
260  ceres::Solver::Summary unused_summary;
261  transform::Rigid3d constraint_transform;
262  ceres_scan_matcher_.Match(match_result->pose_estimate.translation(),
263  match_result->pose_estimate,
264  {{&constant_data->high_resolution_point_cloud,
265  submap_scan_matcher.high_resolution_hybrid_grid},
266  {&constant_data->low_resolution_point_cloud,
267  submap_scan_matcher.low_resolution_hybrid_grid}},
268  &constraint_transform, &unused_summary);
269 
270  constraint->reset(new Constraint{
271  submap_id,
272  node_id,
273  {constraint_transform, options_.loop_closure_translation_weight(),
274  options_.loop_closure_rotation_weight()},
276 
277  if (options_.log_matches()) {
278  std::ostringstream info;
279  info << "Node " << node_id << " with "
280  << constant_data->high_resolution_point_cloud.size()
281  << " points on submap " << submap_id << std::fixed;
282  if (match_full_submap) {
283  info << " matches";
284  } else {
285  // Compute the difference between (submap i <- node j) according to loop
286  // closure ('constraint_transform') and according to global SLAM state.
287  const transform::Rigid3d difference = global_node_pose.inverse() *
288  global_submap_pose *
289  constraint_transform;
290  info << " differs by translation " << std::setprecision(2)
291  << difference.translation().norm() << " rotation "
292  << std::setprecision(3) << transform::GetAngle(difference);
293  }
294  info << " with score " << std::setprecision(1) << 100. * match_result->score
295  << "%.";
296  LOG(INFO) << info.str();
297  }
298 }
299 
301  Result result;
302  std::unique_ptr<std::function<void(const Result&)>> callback;
303  {
304  common::MutexLocker locker(&mutex_);
305  CHECK(when_done_ != nullptr);
306  for (const std::unique_ptr<Constraint>& constraint : constraints_) {
307  if (constraint == nullptr) continue;
308  result.push_back(*constraint);
309  }
310  if (options_.log_matches()) {
311  LOG(INFO) << constraints_.size() << " computations resulted in "
312  << result.size() << " additional constraints.\n"
313  << "Score histogram:\n"
314  << score_histogram_.ToString(10) << "\n"
315  << "Rotational score histogram:\n"
316  << rotational_score_histogram_.ToString(10) << "\n"
317  << "Low resolution score histogram:\n"
318  << low_resolution_score_histogram_.ToString(10);
319  }
320  constraints_.clear();
321  callback = std::move(when_done_);
322  when_done_.reset();
323  kQueueLengthMetric->Set(constraints_.size());
324  }
325  (*callback)(result);
326 }
327 
329  common::MutexLocker locker(&mutex_);
330  return num_finished_nodes_;
331 }
332 
334  common::MutexLocker locker(&mutex_);
335  if (when_done_) {
336  LOG(WARNING)
337  << "DeleteScanMatcher was called while WhenDone was scheduled.";
338  }
339  submap_scan_matchers_.erase(submap_id);
340 }
341 
343  auto* counts = factory->NewCounterFamily(
344  "mapping_internal_constraints_constraint_builder_3d_constraints",
345  "Constraints computed");
347  counts->Add({{"search_region", "local"}, {"matcher", "searched"}});
349  counts->Add({{"search_region", "local"}, {"matcher", "found"}});
351  counts->Add({{"search_region", "global"}, {"matcher", "searched"}});
353  counts->Add({{"search_region", "global"}, {"matcher", "found"}});
354  auto* queue_length = factory->NewGaugeFamily(
355  "mapping_internal_constraints_constraint_builder_3d_queue_length",
356  "Queue length");
357  kQueueLengthMetric = queue_length->Add({});
358  auto boundaries = metrics::Histogram::FixedWidth(0.05, 20);
359  auto* scores = factory->NewHistogramFamily(
360  "mapping_internal_constraints_constraint_builder_3d_scores",
361  "Constraint scores built", boundaries);
363  scores->Add({{"search_region", "local"}, {"kind", "score"}});
365  scores->Add({{"search_region", "local"}, {"kind", "rotational_score"}});
367  {{"search_region", "local"}, {"kind", "low_resolution_score"}});
369  scores->Add({{"search_region", "global"}, {"kind", "score"}});
371  scores->Add({{"search_region", "global"}, {"kind", "rotational_score"}});
373  {{"search_region", "global"}, {"kind", "low_resolution_score"}});
374 }
375 
376 } // namespace constraints
377 } // namespace mapping
378 } // namespace cartographer
static void RegisterMetrics(metrics::FamilyFactory *family_factory)
static Rigid3 Rotation(const AngleAxis &angle_axis)
virtual Family< Gauge > * NewGaugeFamily(const std::string &name, const std::string &description)=0
_Unique_if< T >::_Single_object make_unique(Args &&... args)
Definition: make_unique.h:46
std::unique_ptr< CeresScanMatcher2D > ceres_scan_matcher_
const HybridGrid & high_resolution_hybrid_grid() const
Definition: submap_3d.h:56
#define EXCLUDES(...)
Definition: mutex.h:53
std::unique_ptr< scan_matching::FastCorrelativeScanMatcher3D > fast_correlative_scan_matcher
virtual Family< Counter > * NewCounterFamily(const std::string &name, const std::string &description)=0
const HybridGrid & low_resolution_hybrid_grid() const
Definition: submap_3d.h:59
virtual Family< Histogram > * NewHistogramFamily(const std::string &name, const std::string &description, const Histogram::BucketBoundaries &boundaries)=0
const Quaternion & rotation() const
FakeThreadPool thread_pool_
Definition: task_test.cc:70
void WhenDone(const std::function< void(const Result &)> &callback)
proto::ProbabilityGridRangeDataInserterOptions2D options_
static BucketBoundaries FixedWidth(double width, int num_finite_buckets)
const SubmapScanMatcher * DispatchScanMatcherConstruction(const SubmapId &submap_id, const std::vector< TrajectoryNode > &submap_nodes, const Submap3D *submap) REQUIRES(mutex_)
const Vector & translation() const
void Match(const Eigen::Vector3d &target_translation, const transform::Rigid3d &initial_pose_estimate, const std::vector< PointCloudAndHybridGridPointers > &point_clouds_and_hybrid_grids, transform::Rigid3d *pose_estimate, ceres::Solver::Summary *summary)
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_)
FloatType GetAngle(const Rigid3< FloatType > &transform)
Definition: transform.h:34
static Counter * Null()
Definition: counter.cc:33
virtual std::weak_ptr< Task > Schedule(std::unique_ptr< Task > task)=0
Mutex::Locker MutexLocker
Definition: mutex.h:95
ConstraintBuilder3D(const proto::ConstraintBuilderOptions &options, common::ThreadPoolInterface *thread_pool)
static Gauge * Null()
Definition: gauge.cc:36


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