28 #include "Eigen/Eigenvalues" 32 #include "cartographer/mapping_2d/scan_matching/proto/ceres_scan_matcher_options.pb.h" 33 #include "cartographer/mapping_2d/scan_matching/proto/fast_correlative_scan_matcher_options.pb.h" 35 #include "glog/logging.h" 38 namespace mapping_2d {
39 namespace sparse_pose_graph {
46 const mapping::sparse_pose_graph::proto::ConstraintBuilderOptions& options,
50 sampler_(options.sampling_ratio()),
51 adaptive_voxel_filter_(options.adaptive_voxel_filter_options()),
56 CHECK_EQ(constraints_.size(), 0) <<
"WhenDone() was not called";
57 CHECK_EQ(pending_computations_.size(), 0);
58 CHECK_EQ(submap_queued_work_items_.size(), 0);
59 CHECK(when_done_ ==
nullptr);
67 options_.max_constraint_distance()) {
72 constraints_.emplace_back();
73 auto*
const constraint = &constraints_.back();
74 ++pending_computations_[current_computation_];
75 const int current_computation = current_computation_;
81 point_cloud, initial_relative_pose, constraint);
92 constraints_.emplace_back();
93 auto*
const constraint = &constraints_.back();
94 ++pending_computations_[current_computation_];
95 const int current_computation = current_computation_;
100 trajectory_connectivity, point_cloud,
108 ++current_computation_;
114 CHECK(when_done_ ==
nullptr);
116 common::make_unique<std::function<void(const Result&)>>(callback);
117 ++pending_computations_[current_computation_];
118 const int current_computation = current_computation_;
125 const std::function<
void()> work_item) {
126 if (submap_scan_matchers_[submap_id].fast_correlative_scan_matcher !=
130 submap_queued_work_items_[submap_id].push_back(work_item);
131 if (submap_queued_work_items_[submap_id].size() == 1) {
140 auto submap_scan_matcher =
141 common::make_unique<scan_matching::FastCorrelativeScanMatcher>(
142 *submap,
options_.fast_correlative_scan_matcher_options());
144 submap_scan_matchers_[submap_id] = {submap, std::move(submap_scan_matcher)};
145 for (
const std::function<
void()>& work_item :
146 submap_queued_work_items_[submap_id]) {
149 submap_queued_work_items_.erase(submap_id);
156 &submap_scan_matchers_[submap_id];
158 return submap_scan_matcher;
167 std::unique_ptr<ConstraintBuilder::Constraint>* constraint) {
183 if (match_full_submap) {
185 filtered_point_cloud,
options_.global_localization_min_score(),
186 &score, &pose_estimate)) {
187 CHECK_GT(score,
options_.global_localization_min_score());
197 initial_pose, filtered_point_cloud,
options_.min_score(), &score,
200 CHECK_GT(score,
options_.min_score());
207 score_histogram_.Add(score);
213 ceres::Solver::Summary unused_summary;
216 &pose_estimate, &unused_summary);
223 options_.loop_closure_translation_weight(),
224 options_.loop_closure_rotation_weight()},
228 std::ostringstream info;
229 info <<
"Node " << node_id <<
" with " << filtered_point_cloud.size()
230 <<
" points on submap " << submap_id << std::fixed;
231 if (match_full_submap) {
235 initial_pose.
inverse() * pose_estimate;
236 info <<
" differs by translation " << std::setprecision(2)
240 info <<
" with score " << std::setprecision(1) << 100. * score <<
"%.";
241 LOG(INFO) << info.str();
247 std::unique_ptr<std::function<void(const Result&)>> callback;
250 if (--pending_computations_[computation_index] == 0) {
251 pending_computations_.erase(computation_index);
253 if (pending_computations_.empty()) {
254 CHECK_EQ(submap_queued_work_items_.size(), 0);
255 if (when_done_ !=
nullptr) {
256 for (
const std::unique_ptr<Constraint>& constraint : constraints_) {
257 if (constraint !=
nullptr) {
258 result.push_back(*constraint);
262 LOG(INFO) << constraints_.size() <<
" computations resulted in " 263 << result.size() <<
" additional constraints.";
264 LOG(INFO) <<
"Score histogram:\n" << score_histogram_.ToString(10);
266 constraints_.clear();
267 callback = std::move(when_done_);
272 if (callback !=
nullptr) {
279 if (pending_computations_.empty()) {
280 return current_computation_;
282 return pending_computations_.begin()->first;
287 CHECK(pending_computations_.empty());
288 submap_scan_matchers_.erase(submap_id);
proto::RangeDataInserterOptions options_
common::ThreadPool thread_pool_
int GetNumFinishedScans()
const ProbabilityGrid * probability_grid
void WhenDone(std::function< void(const Result &)> callback)
void DeleteScanMatcher(const mapping::SubmapId &submap_id)
const mapping_2d::ProbabilityGrid * finished_probability_grid() const
void ConstructSubmapScanMatcher(const mapping::SubmapId &submap_id, const ProbabilityGrid *submap) EXCLUDES(mutex_)
transform::Rigid3d local_pose() const
std::unique_ptr< scan_matching::FastCorrelativeScanMatcher > fast_correlative_scan_matcher
void FinishComputation(int computation_index) EXCLUDES(mutex_)
transform::Rigid2d ComputeSubmapPose(const mapping::Submap &submap)
PointCloud Filter(const PointCloud &point_cloud) const
void ScheduleSubmapScanMatcherConstructionAndQueueWorkItem(const mapping::SubmapId &submap_id, const ProbabilityGrid *submap, std::function< void()> work_item) REQUIRES(mutex_)
void Schedule(std::function< void()> work_item)
std::vector< Constraint > Result
ConstraintBuilder(const mapping::sparse_pose_graph::proto::ConstraintBuilderOptions &options, common::ThreadPool *thread_pool)
void MaybeAddConstraint(const mapping::SubmapId &submap_id, const mapping::Submap *submap, const mapping::NodeId &node_id, const sensor::PointCloud *point_cloud, const transform::Rigid2d &initial_relative_pose)
void Connect(int trajectory_id_a, int trajectory_id_b) EXCLUDES(lock_)
const mapping::sparse_pose_graph::proto::ConstraintBuilderOptions options_
common::FixedRatioSampler sampler_
void MaybeAddGlobalConstraint(const mapping::SubmapId &submap_id, const mapping::Submap *submap, const mapping::NodeId &node_id, const sensor::PointCloud *point_cloud, mapping::TrajectoryConnectivity *trajectory_connectivity)
std::vector< Eigen::Vector3f > PointCloud
void Match(const transform::Rigid2d &previous_pose, const transform::Rigid2d &initial_pose_estimate, const sensor::PointCloud &point_cloud, const ProbabilityGrid &probability_grid, transform::Rigid2d *pose_estimate, ceres::Solver::Summary *summary) const
common::ThreadPool * thread_pool_
const sensor::AdaptiveVoxelFilter adaptive_voxel_filter_
scan_matching::CeresScanMatcher ceres_scan_matcher_
const SubmapScanMatcher * GetSubmapScanMatcher(const mapping::SubmapId &submap_id) EXCLUDES(mutex_)
Mutex::Locker MutexLocker
void ComputeConstraint(const mapping::SubmapId &submap_id, const mapping::Submap *submap, const mapping::NodeId &node_id, bool match_full_submap, mapping::TrajectoryConnectivity *trajectory_connectivity, const sensor::PointCloud *point_cloud, const transform::Rigid2d &initial_relative_pose, std::unique_ptr< Constraint > *constraint) EXCLUDES(mutex_)
std::unique_ptr< CeresScanMatcher > ceres_scan_matcher_