constraint_builder_2d.cc
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #include "cartographer/mapping/internal/constraints/constraint_builder_2d.h"
00018 
00019 #include <cmath>
00020 #include <functional>
00021 #include <iomanip>
00022 #include <iostream>
00023 #include <limits>
00024 #include <memory>
00025 #include <sstream>
00026 #include <string>
00027 
00028 #include "Eigen/Eigenvalues"
00029 #include "absl/memory/memory.h"
00030 #include "cartographer/common/math.h"
00031 #include "cartographer/common/thread_pool.h"
00032 #include "cartographer/mapping/proto/scan_matching//ceres_scan_matcher_options_2d.pb.h"
00033 #include "cartographer/mapping/proto/scan_matching//fast_correlative_scan_matcher_options_2d.pb.h"
00034 #include "cartographer/metrics/counter.h"
00035 #include "cartographer/metrics/gauge.h"
00036 #include "cartographer/metrics/histogram.h"
00037 #include "cartographer/transform/transform.h"
00038 #include "glog/logging.h"
00039 
00040 namespace cartographer {
00041 namespace mapping {
00042 namespace constraints {
00043 
00044 static auto* kConstraintsSearchedMetric = metrics::Counter::Null();
00045 static auto* kConstraintsFoundMetric = metrics::Counter::Null();
00046 static auto* kGlobalConstraintsSearchedMetric = metrics::Counter::Null();
00047 static auto* kGlobalConstraintsFoundMetric = metrics::Counter::Null();
00048 static auto* kQueueLengthMetric = metrics::Gauge::Null();
00049 static auto* kConstraintScoresMetric = metrics::Histogram::Null();
00050 static auto* kGlobalConstraintScoresMetric = metrics::Histogram::Null();
00051 
00052 transform::Rigid2d ComputeSubmapPose(const Submap2D& submap) {
00053   return transform::Project2D(submap.local_pose());
00054 }
00055 
00056 ConstraintBuilder2D::ConstraintBuilder2D(
00057     const constraints::proto::ConstraintBuilderOptions& options,
00058     common::ThreadPoolInterface* const thread_pool)
00059     : options_(options),
00060       thread_pool_(thread_pool),
00061       finish_node_task_(absl::make_unique<common::Task>()),
00062       when_done_task_(absl::make_unique<common::Task>()),
00063       sampler_(options.sampling_ratio()),
00064       ceres_scan_matcher_(options.ceres_scan_matcher_options()) {}
00065 
00066 ConstraintBuilder2D::~ConstraintBuilder2D() {
00067   absl::MutexLock locker(&mutex_);
00068   CHECK_EQ(finish_node_task_->GetState(), common::Task::NEW);
00069   CHECK_EQ(when_done_task_->GetState(), common::Task::NEW);
00070   CHECK_EQ(constraints_.size(), 0) << "WhenDone() was not called";
00071   CHECK_EQ(num_started_nodes_, num_finished_nodes_);
00072   CHECK(when_done_ == nullptr);
00073 }
00074 
00075 void ConstraintBuilder2D::MaybeAddConstraint(
00076     const SubmapId& submap_id, const Submap2D* const submap,
00077     const NodeId& node_id, const TrajectoryNode::Data* const constant_data,
00078     const transform::Rigid2d& initial_relative_pose) {
00079   if (initial_relative_pose.translation().norm() >
00080       options_.max_constraint_distance()) {
00081     return;
00082   }
00083   if (!sampler_.Pulse()) return;
00084 
00085   absl::MutexLock locker(&mutex_);
00086   if (when_done_) {
00087     LOG(WARNING)
00088         << "MaybeAddConstraint was called while WhenDone was scheduled.";
00089   }
00090   constraints_.emplace_back();
00091   kQueueLengthMetric->Set(constraints_.size());
00092   auto* const constraint = &constraints_.back();
00093   const auto* scan_matcher =
00094       DispatchScanMatcherConstruction(submap_id, submap->grid());
00095   auto constraint_task = absl::make_unique<common::Task>();
00096   constraint_task->SetWorkItem([=]() LOCKS_EXCLUDED(mutex_) {
00097     ComputeConstraint(submap_id, submap, node_id, false, /* match_full_submap */
00098                       constant_data, initial_relative_pose, *scan_matcher,
00099                       constraint);
00100   });
00101   constraint_task->AddDependency(scan_matcher->creation_task_handle);
00102   auto constraint_task_handle =
00103       thread_pool_->Schedule(std::move(constraint_task));
00104   finish_node_task_->AddDependency(constraint_task_handle);
00105 }
00106 
00107 void ConstraintBuilder2D::MaybeAddGlobalConstraint(
00108     const SubmapId& submap_id, const Submap2D* const submap,
00109     const NodeId& node_id, const TrajectoryNode::Data* const constant_data) {
00110   absl::MutexLock locker(&mutex_);
00111   if (when_done_) {
00112     LOG(WARNING)
00113         << "MaybeAddGlobalConstraint was called while WhenDone was scheduled.";
00114   }
00115   constraints_.emplace_back();
00116   kQueueLengthMetric->Set(constraints_.size());
00117   auto* const constraint = &constraints_.back();
00118   const auto* scan_matcher =
00119       DispatchScanMatcherConstruction(submap_id, submap->grid());
00120   auto constraint_task = absl::make_unique<common::Task>();
00121   constraint_task->SetWorkItem([=]() LOCKS_EXCLUDED(mutex_) {
00122     ComputeConstraint(submap_id, submap, node_id, true, /* match_full_submap */
00123                       constant_data, transform::Rigid2d::Identity(),
00124                       *scan_matcher, constraint);
00125   });
00126   constraint_task->AddDependency(scan_matcher->creation_task_handle);
00127   auto constraint_task_handle =
00128       thread_pool_->Schedule(std::move(constraint_task));
00129   finish_node_task_->AddDependency(constraint_task_handle);
00130 }
00131 
00132 void ConstraintBuilder2D::NotifyEndOfNode() {
00133   absl::MutexLock locker(&mutex_);
00134   CHECK(finish_node_task_ != nullptr);
00135   finish_node_task_->SetWorkItem([this] {
00136     absl::MutexLock locker(&mutex_);
00137     ++num_finished_nodes_;
00138   });
00139   auto finish_node_task_handle =
00140       thread_pool_->Schedule(std::move(finish_node_task_));
00141   finish_node_task_ = absl::make_unique<common::Task>();
00142   when_done_task_->AddDependency(finish_node_task_handle);
00143   ++num_started_nodes_;
00144 }
00145 
00146 void ConstraintBuilder2D::WhenDone(
00147     const std::function<void(const ConstraintBuilder2D::Result&)>& callback) {
00148   absl::MutexLock locker(&mutex_);
00149   CHECK(when_done_ == nullptr);
00150   // TODO(gaschler): Consider using just std::function, it can also be empty.
00151   when_done_ = absl::make_unique<std::function<void(const Result&)>>(callback);
00152   CHECK(when_done_task_ != nullptr);
00153   when_done_task_->SetWorkItem([this] { RunWhenDoneCallback(); });
00154   thread_pool_->Schedule(std::move(when_done_task_));
00155   when_done_task_ = absl::make_unique<common::Task>();
00156 }
00157 
00158 const ConstraintBuilder2D::SubmapScanMatcher*
00159 ConstraintBuilder2D::DispatchScanMatcherConstruction(const SubmapId& submap_id,
00160                                                      const Grid2D* const grid) {
00161   CHECK(grid);
00162   if (submap_scan_matchers_.count(submap_id) != 0) {
00163     return &submap_scan_matchers_.at(submap_id);
00164   }
00165   auto& submap_scan_matcher = submap_scan_matchers_[submap_id];
00166   submap_scan_matcher.grid = grid;
00167   auto& scan_matcher_options = options_.fast_correlative_scan_matcher_options();
00168   auto scan_matcher_task = absl::make_unique<common::Task>();
00169   scan_matcher_task->SetWorkItem(
00170       [&submap_scan_matcher, &scan_matcher_options]() {
00171         submap_scan_matcher.fast_correlative_scan_matcher =
00172             absl::make_unique<scan_matching::FastCorrelativeScanMatcher2D>(
00173                 *submap_scan_matcher.grid, scan_matcher_options);
00174       });
00175   submap_scan_matcher.creation_task_handle =
00176       thread_pool_->Schedule(std::move(scan_matcher_task));
00177   return &submap_scan_matchers_.at(submap_id);
00178 }
00179 
00180 void ConstraintBuilder2D::ComputeConstraint(
00181     const SubmapId& submap_id, const Submap2D* const submap,
00182     const NodeId& node_id, bool match_full_submap,
00183     const TrajectoryNode::Data* const constant_data,
00184     const transform::Rigid2d& initial_relative_pose,
00185     const SubmapScanMatcher& submap_scan_matcher,
00186     std::unique_ptr<ConstraintBuilder2D::Constraint>* constraint) {
00187   CHECK(submap_scan_matcher.fast_correlative_scan_matcher);
00188   const transform::Rigid2d initial_pose =
00189       ComputeSubmapPose(*submap) * initial_relative_pose;
00190 
00191   // The 'constraint_transform' (submap i <- node j) is computed from:
00192   // - a 'filtered_gravity_aligned_point_cloud' in node j,
00193   // - the initial guess 'initial_pose' for (map <- node j),
00194   // - the result 'pose_estimate' of Match() (map <- node j).
00195   // - the ComputeSubmapPose() (map <- submap i)
00196   float score = 0.;
00197   transform::Rigid2d pose_estimate = transform::Rigid2d::Identity();
00198 
00199   // Compute 'pose_estimate' in three stages:
00200   // 1. Fast estimate using the fast correlative scan matcher.
00201   // 2. Prune if the score is too low.
00202   // 3. Refine.
00203   if (match_full_submap) {
00204     kGlobalConstraintsSearchedMetric->Increment();
00205     if (submap_scan_matcher.fast_correlative_scan_matcher->MatchFullSubmap(
00206             constant_data->filtered_gravity_aligned_point_cloud,
00207             options_.global_localization_min_score(), &score, &pose_estimate)) {
00208       CHECK_GT(score, options_.global_localization_min_score());
00209       CHECK_GE(node_id.trajectory_id, 0);
00210       CHECK_GE(submap_id.trajectory_id, 0);
00211       kGlobalConstraintsFoundMetric->Increment();
00212       kGlobalConstraintScoresMetric->Observe(score);
00213     } else {
00214       return;
00215     }
00216   } else {
00217     kConstraintsSearchedMetric->Increment();
00218     if (submap_scan_matcher.fast_correlative_scan_matcher->Match(
00219             initial_pose, constant_data->filtered_gravity_aligned_point_cloud,
00220             options_.min_score(), &score, &pose_estimate)) {
00221       // We've reported a successful local match.
00222       CHECK_GT(score, options_.min_score());
00223       kConstraintsFoundMetric->Increment();
00224       kConstraintScoresMetric->Observe(score);
00225     } else {
00226       return;
00227     }
00228   }
00229   {
00230     absl::MutexLock locker(&mutex_);
00231     score_histogram_.Add(score);
00232   }
00233 
00234   // Use the CSM estimate as both the initial and previous pose. This has the
00235   // effect that, in the absence of better information, we prefer the original
00236   // CSM estimate.
00237   ceres::Solver::Summary unused_summary;
00238   ceres_scan_matcher_.Match(pose_estimate.translation(), pose_estimate,
00239                             constant_data->filtered_gravity_aligned_point_cloud,
00240                             *submap_scan_matcher.grid, &pose_estimate,
00241                             &unused_summary);
00242 
00243   const transform::Rigid2d constraint_transform =
00244       ComputeSubmapPose(*submap).inverse() * pose_estimate;
00245   constraint->reset(new Constraint{submap_id,
00246                                    node_id,
00247                                    {transform::Embed3D(constraint_transform),
00248                                     options_.loop_closure_translation_weight(),
00249                                     options_.loop_closure_rotation_weight()},
00250                                    Constraint::INTER_SUBMAP});
00251 
00252   if (options_.log_matches()) {
00253     std::ostringstream info;
00254     info << "Node " << node_id << " with "
00255          << constant_data->filtered_gravity_aligned_point_cloud.size()
00256          << " points on submap " << submap_id << std::fixed;
00257     if (match_full_submap) {
00258       info << " matches";
00259     } else {
00260       const transform::Rigid2d difference =
00261           initial_pose.inverse() * pose_estimate;
00262       info << " differs by translation " << std::setprecision(2)
00263            << difference.translation().norm() << " rotation "
00264            << std::setprecision(3) << std::abs(difference.normalized_angle());
00265     }
00266     info << " with score " << std::setprecision(1) << 100. * score << "%.";
00267     LOG(INFO) << info.str();
00268   }
00269 }
00270 
00271 void ConstraintBuilder2D::RunWhenDoneCallback() {
00272   Result result;
00273   std::unique_ptr<std::function<void(const Result&)>> callback;
00274   {
00275     absl::MutexLock locker(&mutex_);
00276     CHECK(when_done_ != nullptr);
00277     for (const std::unique_ptr<Constraint>& constraint : constraints_) {
00278       if (constraint == nullptr) continue;
00279       result.push_back(*constraint);
00280     }
00281     if (options_.log_matches()) {
00282       LOG(INFO) << constraints_.size() << " computations resulted in "
00283                 << result.size() << " additional constraints.";
00284       LOG(INFO) << "Score histogram:\n" << score_histogram_.ToString(10);
00285     }
00286     constraints_.clear();
00287     callback = std::move(when_done_);
00288     when_done_.reset();
00289     kQueueLengthMetric->Set(constraints_.size());
00290   }
00291   (*callback)(result);
00292 }
00293 
00294 int ConstraintBuilder2D::GetNumFinishedNodes() {
00295   absl::MutexLock locker(&mutex_);
00296   return num_finished_nodes_;
00297 }
00298 
00299 void ConstraintBuilder2D::DeleteScanMatcher(const SubmapId& submap_id) {
00300   absl::MutexLock locker(&mutex_);
00301   if (when_done_) {
00302     LOG(WARNING)
00303         << "DeleteScanMatcher was called while WhenDone was scheduled.";
00304   }
00305   submap_scan_matchers_.erase(submap_id);
00306 }
00307 
00308 void ConstraintBuilder2D::RegisterMetrics(metrics::FamilyFactory* factory) {
00309   auto* counts = factory->NewCounterFamily(
00310       "mapping_constraints_constraint_builder_2d_constraints",
00311       "Constraints computed");
00312   kConstraintsSearchedMetric =
00313       counts->Add({{"search_region", "local"}, {"matcher", "searched"}});
00314   kConstraintsFoundMetric =
00315       counts->Add({{"search_region", "local"}, {"matcher", "found"}});
00316   kGlobalConstraintsSearchedMetric =
00317       counts->Add({{"search_region", "global"}, {"matcher", "searched"}});
00318   kGlobalConstraintsFoundMetric =
00319       counts->Add({{"search_region", "global"}, {"matcher", "found"}});
00320   auto* queue_length = factory->NewGaugeFamily(
00321       "mapping_constraints_constraint_builder_2d_queue_length", "Queue length");
00322   kQueueLengthMetric = queue_length->Add({});
00323   auto boundaries = metrics::Histogram::FixedWidth(0.05, 20);
00324   auto* scores = factory->NewHistogramFamily(
00325       "mapping_constraints_constraint_builder_2d_scores",
00326       "Constraint scores built", boundaries);
00327   kConstraintScoresMetric = scores->Add({{"search_region", "local"}});
00328   kGlobalConstraintScoresMetric = scores->Add({{"search_region", "global"}});
00329 }
00330 
00331 }  // namespace constraints
00332 }  // namespace mapping
00333 }  // namespace cartographer


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:35