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" 42 namespace constraints {
59 const proto::ConstraintBuilderOptions& options,
63 finish_node_task_(common::
make_unique<common::Task>()),
64 when_done_task_(common::
make_unique<common::Task>()),
65 sampler_(options.sampling_ratio()),
72 CHECK_EQ(constraints_.size(), 0) <<
"WhenDone() was not called";
73 CHECK_EQ(num_started_nodes_, num_finished_nodes_);
74 CHECK(when_done_ ==
nullptr);
80 const std::vector<TrajectoryNode>& submap_nodes,
84 .norm() >
options_.max_constraint_distance()) {
92 <<
"MaybeAddConstraint was called while WhenDone was scheduled.";
94 constraints_.emplace_back();
96 auto*
const constraint = &constraints_.back();
97 const auto* scan_matcher =
99 auto constraint_task = common::make_unique<common::Task>();
102 constant_data, global_node_pose, global_submap_pose,
103 *scan_matcher, constraint);
105 constraint_task->AddDependency(scan_matcher->creation_task_handle);
106 auto constraint_task_handle =
108 finish_node_task_->AddDependency(constraint_task_handle);
114 const std::vector<TrajectoryNode>& submap_nodes,
115 const Eigen::Quaterniond& global_node_rotation,
116 const Eigen::Quaterniond& global_submap_rotation) {
120 <<
"MaybeAddGlobalConstraint was called while WhenDone was scheduled.";
122 constraints_.emplace_back();
124 auto*
const constraint = &constraints_.back();
125 const auto* scan_matcher =
127 auto constraint_task = common::make_unique<common::Task>();
133 *scan_matcher, constraint);
135 constraint_task->AddDependency(scan_matcher->creation_task_handle);
136 auto constraint_task_handle =
138 finish_node_task_->AddDependency(constraint_task_handle);
143 CHECK(finish_node_task_ !=
nullptr);
144 finish_node_task_->SetWorkItem([
this] {
146 ++num_finished_nodes_;
148 auto finish_node_task_handle =
150 finish_node_task_ = common::make_unique<common::Task>();
151 when_done_task_->AddDependency(finish_node_task_handle);
152 ++num_started_nodes_;
158 CHECK(when_done_ ==
nullptr);
161 common::make_unique<std::function<void(const Result&)>>(callback);
162 CHECK(when_done_task_ !=
nullptr);
165 when_done_task_ = common::make_unique<common::Task>();
170 const SubmapId& submap_id,
const std::vector<TrajectoryNode>& submap_nodes,
172 if (submap_scan_matchers_.count(submap_id) != 0) {
173 return &submap_scan_matchers_.at(submap_id);
175 auto& submap_scan_matcher = submap_scan_matchers_[submap_id];
178 submap_scan_matcher.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);
191 submap_scan_matcher.creation_task_handle =
193 return &submap_scan_matchers_.at(submap_id);
197 const SubmapId& submap_id,
const NodeId& node_id,
bool match_full_submap,
202 std::unique_ptr<Constraint>* constraint) {
206 std::unique_ptr<scan_matching::FastCorrelativeScanMatcher3D::Result>
213 if (match_full_submap) {
218 *constant_data,
options_.global_localization_min_score());
219 if (match_result !=
nullptr) {
220 CHECK_GT(match_result->score,
options_.global_localization_min_score());
226 match_result->rotational_score);
228 match_result->low_resolution_score);
235 global_node_pose, global_submap_pose, *constant_data,
237 if (match_result !=
nullptr) {
239 CHECK_GT(match_result->score,
options_.min_score());
243 match_result->rotational_score);
245 match_result->low_resolution_score);
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);
260 ceres::Solver::Summary unused_summary;
263 match_result->pose_estimate,
268 &constraint_transform, &unused_summary);
273 {constraint_transform,
options_.loop_closure_translation_weight(),
274 options_.loop_closure_rotation_weight()},
278 std::ostringstream info;
279 info <<
"Node " << node_id <<
" with " 281 <<
" points on submap " << submap_id << std::fixed;
282 if (match_full_submap) {
289 constraint_transform;
290 info <<
" differs by translation " << std::setprecision(2)
294 info <<
" with score " << std::setprecision(1) << 100. * match_result->score
296 LOG(INFO) << info.str();
302 std::unique_ptr<std::function<void(const Result&)>> callback;
305 CHECK(when_done_ !=
nullptr);
306 for (
const std::unique_ptr<Constraint>& constraint : constraints_) {
307 if (constraint ==
nullptr)
continue;
308 result.push_back(*constraint);
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);
320 constraints_.clear();
321 callback = std::move(when_done_);
330 return num_finished_nodes_;
337 <<
"DeleteScanMatcher was called while WhenDone was scheduled.";
339 submap_scan_matchers_.erase(submap_id);
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"}});
355 "mapping_internal_constraints_constraint_builder_3d_queue_length",
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"}});
static auto * kGlobalConstraintsSearchedMetric
static void RegisterMetrics(metrics::FamilyFactory *family_factory)
sensor::PointCloud high_resolution_point_cloud
const HybridGrid * low_resolution_hybrid_grid
virtual Family< Gauge > * NewGaugeFamily(const std::string &name, const std::string &description)=0
_Unique_if< T >::_Single_object make_unique(Args &&... args)
static auto * kGlobalConstraintScoresMetric
std::unique_ptr< CeresScanMatcher2D > ceres_scan_matcher_
const HybridGrid & high_resolution_hybrid_grid() const
std::vector< Constraint > Result
std::unique_ptr< scan_matching::FastCorrelativeScanMatcher3D > fast_correlative_scan_matcher
const HybridGrid * high_resolution_hybrid_grid
int GetNumFinishedNodes()
static Histogram * Null()
const proto::ConstraintBuilderOptions options_
virtual Family< Counter > * NewCounterFamily(const std::string &name, const std::string &description)=0
void RunWhenDoneCallback() EXCLUDES(mutex_)
const HybridGrid & low_resolution_hybrid_grid() const
virtual Family< Histogram > * NewHistogramFamily(const std::string &name, const std::string &description, const Histogram::BucketBoundaries &boundaries)=0
static auto * kConstraintRotationalScoresMetric
void DeleteScanMatcher(const SubmapId &submap_id)
FakeThreadPool thread_pool_
scan_matching::CeresScanMatcher3D ceres_scan_matcher_
static auto * kConstraintLowResolutionScoresMetric
void WhenDone(const std::function< void(const Result &)> &callback)
proto::ProbabilityGridRangeDataInserterOptions2D options_
static auto * kGlobalConstraintLowResolutionScoresMetric
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_)
static auto * kQueueLengthMetric
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)
static auto * kConstraintsSearchedMetric
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)
common::ThreadPoolInterface * thread_pool_
static auto * kGlobalConstraintsFoundMetric
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_)
static auto * kGlobalConstraintRotationalScoresMetric
virtual std::weak_ptr< Task > Schedule(std::unique_ptr< Task > task)=0
static auto * kConstraintsFoundMetric
sensor::PointCloud low_resolution_point_cloud
Mutex::Locker MutexLocker
ConstraintBuilder3D(const proto::ConstraintBuilderOptions &options, common::ThreadPoolInterface *thread_pool)
common::FixedRatioSampler sampler_
static auto * kConstraintScoresMetric