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" 42 namespace constraints {
57 const constraints::proto::ConstraintBuilderOptions& options,
61 finish_node_task_(common::make_unique<common::Task>()),
62 when_done_task_(common::make_unique<common::Task>()),
63 sampler_(options.sampling_ratio()),
70 CHECK_EQ(constraints_.size(), 0) <<
"WhenDone() was not called";
71 CHECK_EQ(num_started_nodes_, num_finished_nodes_);
72 CHECK(when_done_ ==
nullptr);
80 options_.max_constraint_distance()) {
88 <<
"MaybeAddConstraint was called while WhenDone was scheduled.";
90 constraints_.emplace_back();
92 auto*
const constraint = &constraints_.back();
93 const auto* scan_matcher =
95 auto constraint_task = common::make_unique<common::Task>();
98 constant_data, initial_relative_pose, *scan_matcher,
101 constraint_task->AddDependency(scan_matcher->creation_task_handle);
102 auto constraint_task_handle =
104 finish_node_task_->AddDependency(constraint_task_handle);
113 <<
"MaybeAddGlobalConstraint was called while WhenDone was scheduled.";
115 constraints_.emplace_back();
117 auto*
const constraint = &constraints_.back();
118 const auto* scan_matcher =
120 auto constraint_task = common::make_unique<common::Task>();
124 *scan_matcher, constraint);
126 constraint_task->AddDependency(scan_matcher->creation_task_handle);
127 auto constraint_task_handle =
129 finish_node_task_->AddDependency(constraint_task_handle);
134 CHECK(finish_node_task_ !=
nullptr);
135 finish_node_task_->SetWorkItem([
this] {
137 ++num_finished_nodes_;
139 auto finish_node_task_handle =
141 finish_node_task_ = common::make_unique<common::Task>();
142 when_done_task_->AddDependency(finish_node_task_handle);
143 ++num_started_nodes_;
149 CHECK(when_done_ ==
nullptr);
152 common::make_unique<std::function<void(const Result&)>>(callback);
153 CHECK(when_done_task_ !=
nullptr);
156 when_done_task_ = common::make_unique<common::Task>();
161 const Grid2D*
const grid) {
162 if (submap_scan_matchers_.count(submap_id) != 0) {
163 return &submap_scan_matchers_.at(submap_id);
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);
175 submap_scan_matcher.creation_task_handle =
177 return &submap_scan_matchers_.at(submap_id);
182 const NodeId& node_id,
bool match_full_submap,
186 std::unique_ptr<ConstraintBuilder2D::Constraint>* constraint) {
202 if (match_full_submap) {
206 options_.global_localization_min_score(), &score, &pose_estimate)) {
207 CHECK_GT(score,
options_.global_localization_min_score());
219 options_.min_score(), &score, &pose_estimate)) {
221 CHECK_GT(score,
options_.min_score());
230 score_histogram_.Add(score);
236 ceres::Solver::Summary unused_summary;
239 *submap_scan_matcher.
grid, &pose_estimate,
247 options_.loop_closure_translation_weight(),
248 options_.loop_closure_rotation_weight()},
252 std::ostringstream info;
253 info <<
"Node " << node_id <<
" with " 255 <<
" points on submap " << submap_id << std::fixed;
256 if (match_full_submap) {
260 initial_pose.
inverse() * pose_estimate;
261 info <<
" differs by translation " << std::setprecision(2)
265 info <<
" with score " << std::setprecision(1) << 100. * score <<
"%.";
266 LOG(INFO) << info.str();
272 std::unique_ptr<std::function<void(const Result&)>> callback;
275 CHECK(when_done_ !=
nullptr);
276 for (
const std::unique_ptr<Constraint>& constraint : constraints_) {
277 if (constraint ==
nullptr)
continue;
278 result.push_back(*constraint);
281 LOG(INFO) << constraints_.size() <<
" computations resulted in " 282 << result.size() <<
" additional constraints.";
283 LOG(INFO) <<
"Score histogram:\n" << score_histogram_.ToString(10);
285 constraints_.clear();
286 callback = std::move(when_done_);
295 return num_finished_nodes_;
302 <<
"DeleteScanMatcher was called while WhenDone was scheduled.";
304 submap_scan_matchers_.erase(submap_id);
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"}});
320 "mapping_internal_constraints_constraint_builder_2d_queue_length",
325 "mapping_internal_constraints_constraint_builder_2d_scores",
326 "Constraint scores built", boundaries);
static auto * kGlobalConstraintsSearchedMetric
void DeleteScanMatcher(const SubmapId &submap_id)
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::vector< Constraint > Result
std::unique_ptr< scan_matching::FastCorrelativeScanMatcher2D > fast_correlative_scan_matcher
static auto * kGlobalConstraintScoresMetric
std::unique_ptr< CeresScanMatcher2D > ceres_scan_matcher_
static void RegisterMetrics(metrics::FamilyFactory *family_factory)
static Histogram * Null()
const constraints::proto::ConstraintBuilderOptions options_
virtual Family< Counter > * NewCounterFamily(const std::string &name, const std::string &description)=0
void RunWhenDoneCallback() EXCLUDES(mutex_)
sensor::PointCloud filtered_gravity_aligned_point_cloud
virtual Family< Histogram > * NewHistogramFamily(const std::string &name, const std::string &description, const Histogram::BucketBoundaries &boundaries)=0
common::FixedRatioSampler sampler_
FakeThreadPool thread_pool_
proto::ProbabilityGridRangeDataInserterOptions2D options_
transform::Rigid2d ComputeSubmapPose(const Submap2D &submap)
static BucketBoundaries FixedWidth(double width, int num_finite_buckets)
static auto * kQueueLengthMetric
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)
common::ThreadPoolInterface * thread_pool_
ConstraintBuilder2D(const proto::ConstraintBuilderOptions &options, common::ThreadPoolInterface *thread_pool)
static auto * kConstraintsSearchedMetric
const Grid2D * grid() const
transform::Rigid3d local_pose() const
void MaybeAddGlobalConstraint(const SubmapId &submap_id, const Submap2D *submap, const NodeId &node_id, const TrajectoryNode::Data *const constant_data)
static auto * kGlobalConstraintsFoundMetric
int GetNumFinishedNodes()
virtual std::weak_ptr< Task > Schedule(std::unique_ptr< Task > task)=0
static auto * kConstraintsFoundMetric
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
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_)
scan_matching::CeresScanMatcher2D ceres_scan_matcher_
void WhenDone(const std::function< void(const Result &)> &callback)
static auto * kConstraintScoresMetric