28 #include "Eigen/Eigenvalues" 33 #include "cartographer/mapping_3d/scan_matching/proto/ceres_scan_matcher_options.pb.h" 34 #include "cartographer/mapping_3d/scan_matching/proto/fast_correlative_scan_matcher_options.pb.h" 36 #include "glog/logging.h" 39 namespace mapping_3d {
40 namespace sparse_pose_graph {
43 const mapping::sparse_pose_graph::proto::ConstraintBuilderOptions& options,
47 sampler_(options.sampling_ratio()),
48 adaptive_voxel_filter_(options.adaptive_voxel_filter_options()),
53 CHECK_EQ(constraints_.size(), 0) <<
"WhenDone() was not called";
54 CHECK_EQ(pending_computations_.size(), 0);
55 CHECK_EQ(submap_queued_work_items_.size(), 0);
56 CHECK(when_done_ ==
nullptr);
63 const std::vector<mapping::TrajectoryNode>& submap_nodes,
70 constraints_.emplace_back();
71 auto*
const constraint = &constraints_.back();
72 ++pending_computations_[current_computation_];
73 const int current_computation = current_computation_;
80 compressed_point_cloud, initial_pose, constraint);
90 const std::vector<mapping::TrajectoryNode>& submap_nodes,
91 const Eigen::Quaterniond& gravity_alignment,
94 constraints_.emplace_back();
95 auto*
const constraint = &constraints_.back();
96 ++pending_computations_[current_computation_];
97 const int current_computation = current_computation_;
102 submap_id, submap, node_id,
true,
103 trajectory_connectivity, compressed_point_cloud,
111 ++current_computation_;
117 CHECK(when_done_ ==
nullptr);
119 common::make_unique<std::function<void(const Result&)>>(callback);
120 ++pending_computations_[current_computation_];
121 const int current_computation = current_computation_;
128 const std::vector<mapping::TrajectoryNode>& submap_nodes,
129 const HybridGrid*
const submap,
const std::function<
void()> work_item) {
130 if (submap_scan_matchers_[submap_id].fast_correlative_scan_matcher !=
134 submap_queued_work_items_[submap_id].push_back(work_item);
135 if (submap_queued_work_items_[submap_id].size() == 1) {
145 const std::vector<mapping::TrajectoryNode>& submap_nodes,
147 auto submap_scan_matcher =
148 common::make_unique<scan_matching::FastCorrelativeScanMatcher>(
149 *submap, submap_nodes,
150 options_.fast_correlative_scan_matcher_options_3d());
152 submap_scan_matchers_[submap_id] = {submap, std::move(submap_scan_matcher)};
153 for (
const std::function<
void()>& work_item :
154 submap_queued_work_items_[submap_id]) {
157 submap_queued_work_items_.erase(submap_id);
164 &submap_scan_matchers_[submap_id];
166 return submap_scan_matcher;
175 std::unique_ptr<OptimizationProblem::Constraint>* constraint) {
188 if (match_full_submap) {
190 initial_pose.
rotation(), filtered_point_cloud, point_cloud,
191 options_.global_localization_min_score(), &score, &pose_estimate)) {
192 CHECK_GT(score,
options_.global_localization_min_score());
202 initial_pose, filtered_point_cloud, point_cloud,
203 options_.min_score(), &score, &pose_estimate)) {
205 CHECK_GT(score,
options_.min_score());
212 score_histogram_.Add(score);
218 ceres::Solver::Summary unused_summary;
221 pose_estimate, pose_estimate,
222 {{&filtered_point_cloud, submap_scan_matcher->
hybrid_grid}},
223 &constraint_transform, &unused_summary);
228 {constraint_transform,
options_.loop_closure_translation_weight(),
229 options_.loop_closure_rotation_weight()},
233 std::ostringstream info;
234 info <<
"Node " << node_id <<
" with " << filtered_point_cloud.size()
235 <<
" points on submap " << submap_id << std::fixed;
236 if (match_full_submap) {
240 initial_pose.
inverse() * constraint_transform;
241 info <<
" differs by translation " << std::setprecision(2)
245 info <<
" with score " << std::setprecision(1) << 100. * score <<
"%.";
246 LOG(INFO) << info.str();
252 std::unique_ptr<std::function<void(const Result&)>> callback;
255 if (--pending_computations_[computation_index] == 0) {
256 pending_computations_.erase(computation_index);
258 if (pending_computations_.empty()) {
259 CHECK_EQ(submap_queued_work_items_.size(), 0);
260 if (when_done_ !=
nullptr) {
261 for (
const std::unique_ptr<OptimizationProblem::Constraint>&
262 constraint : constraints_) {
263 if (constraint !=
nullptr) {
264 result.push_back(*constraint);
268 LOG(INFO) << constraints_.size() <<
" computations resulted in " 269 << result.size() <<
" additional constraints.";
270 LOG(INFO) <<
"Score histogram:\n" << score_histogram_.ToString(10);
272 constraints_.clear();
273 callback = std::move(when_done_);
278 if (callback !=
nullptr) {
285 if (pending_computations_.empty()) {
286 return current_computation_;
288 return pending_computations_.begin()->first;
PointCloud Decompress() const
proto::RangeDataInserterOptions options_
scan_matching::CeresScanMatcher ceres_scan_matcher_
void MaybeAddGlobalConstraint(const mapping::SubmapId &submap_id, const Submap *submap, const mapping::NodeId &node_id, const sensor::CompressedPointCloud *compressed_point_cloud, const std::vector< mapping::TrajectoryNode > &submap_nodes, const Eigen::Quaterniond &gravity_alignment, mapping::TrajectoryConnectivity *trajectory_connectivity)
common::ThreadPool thread_pool_
const SubmapScanMatcher * GetSubmapScanMatcher(const mapping::SubmapId &submap_id) EXCLUDES(mutex_)
std::vector< Constraint > Result
void ComputeConstraint(const mapping::SubmapId &submap_id, const Submap *submap, const mapping::NodeId &node_id, bool match_full_submap, mapping::TrajectoryConnectivity *trajectory_connectivity, const sensor::CompressedPointCloud *compressed_point_cloud, const transform::Rigid3d &initial_pose, std::unique_ptr< Constraint > *constraint) EXCLUDES(mutex_)
const HybridGrid & high_resolution_hybrid_grid() const
const sensor::AdaptiveVoxelFilter adaptive_voxel_filter_
std::unique_ptr< scan_matching::FastCorrelativeScanMatcher > fast_correlative_scan_matcher
const mapping::sparse_pose_graph::proto::ConstraintBuilderOptions options_
void Match(const transform::Rigid3d &previous_pose, const transform::Rigid3d &initial_pose_estimate, const std::vector< PointCloudAndHybridGridPointers > &point_clouds_and_hybrid_grids, transform::Rigid3d *pose_estimate, ceres::Solver::Summary *summary)
PointCloud Filter(const PointCloud &point_cloud) const
void Schedule(std::function< void()> work_item)
void MaybeAddConstraint(const mapping::SubmapId &submap_id, const Submap *submap, const mapping::NodeId &node_id, const sensor::CompressedPointCloud *compressed_point_cloud, const std::vector< mapping::TrajectoryNode > &submap_nodes, const transform::Rigid3d &initial_pose)
common::ThreadPool * thread_pool_
void Connect(int trajectory_id_a, int trajectory_id_b) EXCLUDES(lock_)
int GetNumFinishedScans()
std::vector< Eigen::Vector3f > PointCloud
void WhenDone(std::function< void(const Result &)> callback)
void ConstructSubmapScanMatcher(const mapping::SubmapId &submap_id, const std::vector< mapping::TrajectoryNode > &submap_nodes, const HybridGrid *submap) EXCLUDES(mutex_)
ConstraintBuilder(const mapping::sparse_pose_graph::proto::ConstraintBuilderOptions &options, common::ThreadPool *thread_pool)
common::FixedRatioSampler sampler_
void ScheduleSubmapScanMatcherConstructionAndQueueWorkItem(const mapping::SubmapId &submap_id, const std::vector< mapping::TrajectoryNode > &submap_nodes, const HybridGrid *submap, std::function< void()> work_item) REQUIRES(mutex_)
const HybridGrid * hybrid_grid
void FinishComputation(int computation_index) EXCLUDES(mutex_)
Mutex::Locker MutexLocker
std::unique_ptr< CeresScanMatcher > ceres_scan_matcher_