00001
00002
00003
00004
00005
00006
00007
00008
00009
00010
00011
00012
00013
00014
00015
00016
00017 #include "cartographer/mapping/internal/constraints/constraint_builder_3d.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_3d.pb.h"
00033 #include "cartographer/mapping/proto/scan_matching//fast_correlative_scan_matcher_options_3d.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* kConstraintRotationalScoresMetric = metrics::Histogram::Null();
00051 static auto* kConstraintLowResolutionScoresMetric = metrics::Histogram::Null();
00052 static auto* kGlobalConstraintScoresMetric = metrics::Histogram::Null();
00053 static auto* kGlobalConstraintRotationalScoresMetric =
00054 metrics::Histogram::Null();
00055 static auto* kGlobalConstraintLowResolutionScoresMetric =
00056 metrics::Histogram::Null();
00057
00058 ConstraintBuilder3D::ConstraintBuilder3D(
00059 const proto::ConstraintBuilderOptions& options,
00060 common::ThreadPoolInterface* const thread_pool)
00061 : options_(options),
00062 thread_pool_(thread_pool),
00063 finish_node_task_(absl::make_unique<common::Task>()),
00064 when_done_task_(absl::make_unique<common::Task>()),
00065 sampler_(options.sampling_ratio()),
00066 ceres_scan_matcher_(options.ceres_scan_matcher_options_3d()) {}
00067
00068 ConstraintBuilder3D::~ConstraintBuilder3D() {
00069 absl::MutexLock locker(&mutex_);
00070 CHECK_EQ(finish_node_task_->GetState(), common::Task::NEW);
00071 CHECK_EQ(when_done_task_->GetState(), common::Task::NEW);
00072 CHECK_EQ(constraints_.size(), 0) << "WhenDone() was not called";
00073 CHECK_EQ(num_started_nodes_, num_finished_nodes_);
00074 CHECK(when_done_ == nullptr);
00075 }
00076
00077 void ConstraintBuilder3D::MaybeAddConstraint(
00078 const SubmapId& submap_id, const Submap3D* const submap,
00079 const NodeId& node_id, const TrajectoryNode::Data* const constant_data,
00080 const transform::Rigid3d& global_node_pose,
00081 const transform::Rigid3d& global_submap_pose) {
00082 if ((global_node_pose.translation() - global_submap_pose.translation())
00083 .norm() > options_.max_constraint_distance()) {
00084 return;
00085 }
00086 if (!sampler_.Pulse()) return;
00087
00088 absl::MutexLock locker(&mutex_);
00089 if (when_done_) {
00090 LOG(WARNING)
00091 << "MaybeAddConstraint was called while WhenDone was scheduled.";
00092 }
00093 constraints_.emplace_back();
00094 kQueueLengthMetric->Set(constraints_.size());
00095 auto* const constraint = &constraints_.back();
00096 const auto* scan_matcher = DispatchScanMatcherConstruction(submap_id, submap);
00097 auto constraint_task = absl::make_unique<common::Task>();
00098 constraint_task->SetWorkItem([=]() LOCKS_EXCLUDED(mutex_) {
00099 ComputeConstraint(submap_id, node_id, false,
00100 constant_data, global_node_pose, global_submap_pose,
00101 *scan_matcher, constraint);
00102 });
00103 constraint_task->AddDependency(scan_matcher->creation_task_handle);
00104 auto constraint_task_handle =
00105 thread_pool_->Schedule(std::move(constraint_task));
00106 finish_node_task_->AddDependency(constraint_task_handle);
00107 }
00108
00109 void ConstraintBuilder3D::MaybeAddGlobalConstraint(
00110 const SubmapId& submap_id, const Submap3D* const submap,
00111 const NodeId& node_id, const TrajectoryNode::Data* const constant_data,
00112 const Eigen::Quaterniond& global_node_rotation,
00113 const Eigen::Quaterniond& global_submap_rotation) {
00114 absl::MutexLock locker(&mutex_);
00115 if (when_done_) {
00116 LOG(WARNING)
00117 << "MaybeAddGlobalConstraint was called while WhenDone was scheduled.";
00118 }
00119 constraints_.emplace_back();
00120 kQueueLengthMetric->Set(constraints_.size());
00121 auto* const constraint = &constraints_.back();
00122 const auto* scan_matcher = DispatchScanMatcherConstruction(submap_id, submap);
00123 auto constraint_task = absl::make_unique<common::Task>();
00124 constraint_task->SetWorkItem([=]() LOCKS_EXCLUDED(mutex_) {
00125 ComputeConstraint(submap_id, node_id, true,
00126 constant_data,
00127 transform::Rigid3d::Rotation(global_node_rotation),
00128 transform::Rigid3d::Rotation(global_submap_rotation),
00129 *scan_matcher, constraint);
00130 });
00131 constraint_task->AddDependency(scan_matcher->creation_task_handle);
00132 auto constraint_task_handle =
00133 thread_pool_->Schedule(std::move(constraint_task));
00134 finish_node_task_->AddDependency(constraint_task_handle);
00135 }
00136
00137 void ConstraintBuilder3D::NotifyEndOfNode() {
00138 absl::MutexLock locker(&mutex_);
00139 CHECK(finish_node_task_ != nullptr);
00140 finish_node_task_->SetWorkItem([this] {
00141 absl::MutexLock locker(&mutex_);
00142 ++num_finished_nodes_;
00143 });
00144 auto finish_node_task_handle =
00145 thread_pool_->Schedule(std::move(finish_node_task_));
00146 finish_node_task_ = absl::make_unique<common::Task>();
00147 when_done_task_->AddDependency(finish_node_task_handle);
00148 ++num_started_nodes_;
00149 }
00150
00151 void ConstraintBuilder3D::WhenDone(
00152 const std::function<void(const ConstraintBuilder3D::Result&)>& callback) {
00153 absl::MutexLock locker(&mutex_);
00154 CHECK(when_done_ == nullptr);
00155
00156 when_done_ = absl::make_unique<std::function<void(const Result&)>>(callback);
00157 CHECK(when_done_task_ != nullptr);
00158 when_done_task_->SetWorkItem([this] { RunWhenDoneCallback(); });
00159 thread_pool_->Schedule(std::move(when_done_task_));
00160 when_done_task_ = absl::make_unique<common::Task>();
00161 }
00162
00163 const ConstraintBuilder3D::SubmapScanMatcher*
00164 ConstraintBuilder3D::DispatchScanMatcherConstruction(const SubmapId& submap_id,
00165 const Submap3D* submap) {
00166 if (submap_scan_matchers_.count(submap_id) != 0) {
00167 return &submap_scan_matchers_.at(submap_id);
00168 }
00169 auto& submap_scan_matcher = submap_scan_matchers_[submap_id];
00170 submap_scan_matcher.high_resolution_hybrid_grid =
00171 &submap->high_resolution_hybrid_grid();
00172 submap_scan_matcher.low_resolution_hybrid_grid =
00173 &submap->low_resolution_hybrid_grid();
00174 auto& scan_matcher_options =
00175 options_.fast_correlative_scan_matcher_options_3d();
00176 const Eigen::VectorXf* histogram =
00177 &submap->rotational_scan_matcher_histogram();
00178 auto scan_matcher_task = absl::make_unique<common::Task>();
00179 scan_matcher_task->SetWorkItem(
00180 [&submap_scan_matcher, &scan_matcher_options, histogram]() {
00181 submap_scan_matcher.fast_correlative_scan_matcher =
00182 absl::make_unique<scan_matching::FastCorrelativeScanMatcher3D>(
00183 *submap_scan_matcher.high_resolution_hybrid_grid,
00184 submap_scan_matcher.low_resolution_hybrid_grid, histogram,
00185 scan_matcher_options);
00186 });
00187 submap_scan_matcher.creation_task_handle =
00188 thread_pool_->Schedule(std::move(scan_matcher_task));
00189 return &submap_scan_matchers_.at(submap_id);
00190 }
00191
00192 void ConstraintBuilder3D::ComputeConstraint(
00193 const SubmapId& submap_id, const NodeId& node_id, bool match_full_submap,
00194 const TrajectoryNode::Data* const constant_data,
00195 const transform::Rigid3d& global_node_pose,
00196 const transform::Rigid3d& global_submap_pose,
00197 const SubmapScanMatcher& submap_scan_matcher,
00198 std::unique_ptr<Constraint>* constraint) {
00199 CHECK(submap_scan_matcher.fast_correlative_scan_matcher);
00200
00201
00202
00203 std::unique_ptr<scan_matching::FastCorrelativeScanMatcher3D::Result>
00204 match_result;
00205
00206
00207
00208
00209
00210 if (match_full_submap) {
00211 kGlobalConstraintsSearchedMetric->Increment();
00212 match_result =
00213 submap_scan_matcher.fast_correlative_scan_matcher->MatchFullSubmap(
00214 global_node_pose.rotation(), global_submap_pose.rotation(),
00215 *constant_data, options_.global_localization_min_score());
00216 if (match_result != nullptr) {
00217 CHECK_GT(match_result->score, options_.global_localization_min_score());
00218 CHECK_GE(node_id.trajectory_id, 0);
00219 CHECK_GE(submap_id.trajectory_id, 0);
00220 kGlobalConstraintsFoundMetric->Increment();
00221 kGlobalConstraintScoresMetric->Observe(match_result->score);
00222 kGlobalConstraintRotationalScoresMetric->Observe(
00223 match_result->rotational_score);
00224 kGlobalConstraintLowResolutionScoresMetric->Observe(
00225 match_result->low_resolution_score);
00226 } else {
00227 return;
00228 }
00229 } else {
00230 kConstraintsSearchedMetric->Increment();
00231 match_result = submap_scan_matcher.fast_correlative_scan_matcher->Match(
00232 global_node_pose, global_submap_pose, *constant_data,
00233 options_.min_score());
00234 if (match_result != nullptr) {
00235
00236 CHECK_GT(match_result->score, options_.min_score());
00237 kConstraintsFoundMetric->Increment();
00238 kConstraintScoresMetric->Observe(match_result->score);
00239 kConstraintRotationalScoresMetric->Observe(
00240 match_result->rotational_score);
00241 kConstraintLowResolutionScoresMetric->Observe(
00242 match_result->low_resolution_score);
00243 } else {
00244 return;
00245 }
00246 }
00247 {
00248 absl::MutexLock locker(&mutex_);
00249 score_histogram_.Add(match_result->score);
00250 rotational_score_histogram_.Add(match_result->rotational_score);
00251 low_resolution_score_histogram_.Add(match_result->low_resolution_score);
00252 }
00253
00254
00255
00256
00257 ceres::Solver::Summary unused_summary;
00258 transform::Rigid3d constraint_transform;
00259 ceres_scan_matcher_.Match(match_result->pose_estimate.translation(),
00260 match_result->pose_estimate,
00261 {{&constant_data->high_resolution_point_cloud,
00262 submap_scan_matcher.high_resolution_hybrid_grid},
00263 {&constant_data->low_resolution_point_cloud,
00264 submap_scan_matcher.low_resolution_hybrid_grid}},
00265 &constraint_transform, &unused_summary);
00266
00267 constraint->reset(new Constraint{
00268 submap_id,
00269 node_id,
00270 {constraint_transform, options_.loop_closure_translation_weight(),
00271 options_.loop_closure_rotation_weight()},
00272 Constraint::INTER_SUBMAP});
00273
00274 if (options_.log_matches()) {
00275 std::ostringstream info;
00276 info << "Node " << node_id << " with "
00277 << constant_data->high_resolution_point_cloud.size()
00278 << " points on submap " << submap_id << std::fixed;
00279 if (match_full_submap) {
00280 info << " matches";
00281 } else {
00282
00283
00284 const transform::Rigid3d difference = global_node_pose.inverse() *
00285 global_submap_pose *
00286 constraint_transform;
00287 info << " differs by translation " << std::setprecision(2)
00288 << difference.translation().norm() << " rotation "
00289 << std::setprecision(3) << transform::GetAngle(difference);
00290 }
00291 info << " with score " << std::setprecision(1) << 100. * match_result->score
00292 << "%.";
00293 LOG(INFO) << info.str();
00294 }
00295 }
00296
00297 void ConstraintBuilder3D::RunWhenDoneCallback() {
00298 Result result;
00299 std::unique_ptr<std::function<void(const Result&)>> callback;
00300 {
00301 absl::MutexLock locker(&mutex_);
00302 CHECK(when_done_ != nullptr);
00303 for (const std::unique_ptr<Constraint>& constraint : constraints_) {
00304 if (constraint == nullptr) continue;
00305 result.push_back(*constraint);
00306 }
00307 if (options_.log_matches()) {
00308 LOG(INFO) << constraints_.size() << " computations resulted in "
00309 << result.size() << " additional constraints.\n"
00310 << "Score histogram:\n"
00311 << score_histogram_.ToString(10) << "\n"
00312 << "Rotational score histogram:\n"
00313 << rotational_score_histogram_.ToString(10) << "\n"
00314 << "Low resolution score histogram:\n"
00315 << low_resolution_score_histogram_.ToString(10);
00316 }
00317 constraints_.clear();
00318 callback = std::move(when_done_);
00319 when_done_.reset();
00320 kQueueLengthMetric->Set(constraints_.size());
00321 }
00322 (*callback)(result);
00323 }
00324
00325 int ConstraintBuilder3D::GetNumFinishedNodes() {
00326 absl::MutexLock locker(&mutex_);
00327 return num_finished_nodes_;
00328 }
00329
00330 void ConstraintBuilder3D::DeleteScanMatcher(const SubmapId& submap_id) {
00331 absl::MutexLock locker(&mutex_);
00332 if (when_done_) {
00333 LOG(WARNING)
00334 << "DeleteScanMatcher was called while WhenDone was scheduled.";
00335 }
00336 submap_scan_matchers_.erase(submap_id);
00337 }
00338
00339 void ConstraintBuilder3D::RegisterMetrics(metrics::FamilyFactory* factory) {
00340 auto* counts = factory->NewCounterFamily(
00341 "mapping_constraints_constraint_builder_3d_constraints",
00342 "Constraints computed");
00343 kConstraintsSearchedMetric =
00344 counts->Add({{"search_region", "local"}, {"matcher", "searched"}});
00345 kConstraintsFoundMetric =
00346 counts->Add({{"search_region", "local"}, {"matcher", "found"}});
00347 kGlobalConstraintsSearchedMetric =
00348 counts->Add({{"search_region", "global"}, {"matcher", "searched"}});
00349 kGlobalConstraintsFoundMetric =
00350 counts->Add({{"search_region", "global"}, {"matcher", "found"}});
00351 auto* queue_length = factory->NewGaugeFamily(
00352 "mapping_constraints_constraint_builder_3d_queue_length", "Queue length");
00353 kQueueLengthMetric = queue_length->Add({});
00354 auto boundaries = metrics::Histogram::FixedWidth(0.05, 20);
00355 auto* scores = factory->NewHistogramFamily(
00356 "mapping_constraints_constraint_builder_3d_scores",
00357 "Constraint scores built", boundaries);
00358 kConstraintScoresMetric =
00359 scores->Add({{"search_region", "local"}, {"kind", "score"}});
00360 kConstraintRotationalScoresMetric =
00361 scores->Add({{"search_region", "local"}, {"kind", "rotational_score"}});
00362 kConstraintLowResolutionScoresMetric = scores->Add(
00363 {{"search_region", "local"}, {"kind", "low_resolution_score"}});
00364 kGlobalConstraintScoresMetric =
00365 scores->Add({{"search_region", "global"}, {"kind", "score"}});
00366 kGlobalConstraintRotationalScoresMetric =
00367 scores->Add({{"search_region", "global"}, {"kind", "rotational_score"}});
00368 kGlobalConstraintLowResolutionScoresMetric = scores->Add(
00369 {{"search_region", "global"}, {"kind", "low_resolution_score"}});
00370 }
00371
00372 }
00373 }
00374 }