real_time_correlative_scan_matcher_2d.h
Go to the documentation of this file.
1 /*
2  * Copyright 2016 The Cartographer Authors
3  *
4  * Licensed under the Apache License, Version 2.0 (the "License");
5  * you may not use this file except in compliance with the License.
6  * You may obtain a copy of the License at
7  *
8  * http://www.apache.org/licenses/LICENSE-2.0
9  *
10  * Unless required by applicable law or agreed to in writing, software
11  * distributed under the License is distributed on an "AS IS" BASIS,
12  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
13  * See the License for the specific language governing permissions and
14  * limitations under the License.
15  */
16 
17 #ifndef CARTOGRAPHER_MAPPING_INTERNAL_2D_SCAN_MATCHING_REAL_TIME_CORRELATIVE_SCAN_MATCHER_2D_H_
18 #define CARTOGRAPHER_MAPPING_INTERNAL_2D_SCAN_MATCHING_REAL_TIME_CORRELATIVE_SCAN_MATCHER_2D_H_
19 
20 // This is an implementation of the algorithm described in "Real-Time
21 // Correlative Scan Matching" by Olson.
22 //
23 // The correlative scan matching algorithm is exhaustively evaluating the scan
24 // matching search space. As described by the paper, the basic steps are:
25 //
26 // 1) Evaluate the probability p(z|xi, m) over the entire 3D search window using
27 // the low-resolution table.
28 // 2) Find the best voxel in the low-resolution 3D space that has not already
29 // been considered. Denote this value as Li. If Li < Hbest, terminate: Hbest is
30 // the best scan matching alignment.
31 // 3) Evaluate the search volume inside voxel i using the high resolution table.
32 // Suppose the log-likelihood of this voxel is Hi. Note that Hi <= Li since the
33 // low-resolution map overestimates the log likelihoods. If Hi > Hbest, set
34 // Hbest = Hi.
35 //
36 // This can be made even faster by transforming the scan exactly once over some
37 // discretized range.
38 
39 #include <iostream>
40 #include <memory>
41 #include <vector>
42 
43 #include "Eigen/Core"
46 #include "cartographer/mapping/proto/scan_matching/real_time_correlative_scan_matcher_options.pb.h"
47 
48 namespace cartographer {
49 namespace mapping {
50 namespace scan_matching {
51 
52 // An implementation of "Real-Time Correlative Scan Matching" by Olson.
54  public:
56  const proto::RealTimeCorrelativeScanMatcherOptions& options);
57 
59  delete;
61  const RealTimeCorrelativeScanMatcher2D&) = delete;
62 
63  // Aligns 'point_cloud' within the 'probability_grid' given an
64  // 'initial_pose_estimate' then updates 'pose_estimate' with the result and
65  // returns the score.
66  double Match(const transform::Rigid2d& initial_pose_estimate,
67  const sensor::PointCloud& point_cloud,
68  const ProbabilityGrid& probability_grid,
69  transform::Rigid2d* pose_estimate) const;
70 
71  // Computes the score for each Candidate2D in a collection. The cost is
72  // computed as the sum of probabilities, different from the Ceres
73  // CostFunctions: http://ceres-solver.org/modeling.html
74  //
75  // Visible for testing.
76  void ScoreCandidates(const ProbabilityGrid& probability_grid,
77  const std::vector<DiscreteScan2D>& discrete_scans,
78  const SearchParameters& search_parameters,
79  std::vector<Candidate2D>* candidates) const;
80 
81  private:
82  std::vector<Candidate2D> GenerateExhaustiveSearchCandidates(
83  const SearchParameters& search_parameters) const;
84 
85  const proto::RealTimeCorrelativeScanMatcherOptions options_;
86 };
87 
88 } // namespace scan_matching
89 } // namespace mapping
90 } // namespace cartographer
91 
92 #endif // CARTOGRAPHER_MAPPING_INTERNAL_2D_SCAN_MATCHING_REAL_TIME_CORRELATIVE_SCAN_MATCHER_2D_H_
void ScoreCandidates(const ProbabilityGrid &probability_grid, const std::vector< DiscreteScan2D > &discrete_scans, const SearchParameters &search_parameters, std::vector< Candidate2D > *candidates) const
std::vector< Candidate2D > GenerateExhaustiveSearchCandidates(const SearchParameters &search_parameters) const
RealTimeCorrelativeScanMatcher2D & operator=(const RealTimeCorrelativeScanMatcher2D &)=delete
RealTimeCorrelativeScanMatcher2D(const proto::RealTimeCorrelativeScanMatcherOptions &options)
std::vector< Eigen::Vector3f > PointCloud
Definition: point_cloud.h:32
double Match(const transform::Rigid2d &initial_pose_estimate, const sensor::PointCloud &point_cloud, const ProbabilityGrid &probability_grid, transform::Rigid2d *pose_estimate) const


cartographer
Author(s): The Cartographer Authors
autogenerated on Mon Feb 28 2022 22:00:58