mapping_3d/scan_matching/real_time_correlative_scan_matcher.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 // A voxel accurate scan matcher, exhaustively evaluating the scan matching
18 // search space.
19 #ifndef CARTOGRAPHER_MAPPING_3D_SCAN_MATCHING_REAL_TIME_CORRELATIVE_SCAN_MATCHER_H_
20 #define CARTOGRAPHER_MAPPING_3D_SCAN_MATCHING_REAL_TIME_CORRELATIVE_SCAN_MATCHER_H_
21 
22 #include <vector>
23 
24 #include "Eigen/Core"
25 #include "cartographer/mapping_2d/scan_matching/proto/real_time_correlative_scan_matcher_options.pb.h"
28 
29 namespace cartographer {
30 namespace mapping_3d {
31 namespace scan_matching {
32 
34  public:
36  const mapping_2d::scan_matching::proto::
37  RealTimeCorrelativeScanMatcherOptions& options);
38 
40  delete;
42  const RealTimeCorrelativeScanMatcher&) = delete;
43 
44  // Aligns 'point_cloud' within the 'hybrid_grid' given an
45  // 'initial_pose_estimate' then updates 'pose_estimate' with the result and
46  // returns the score.
47  float Match(const transform::Rigid3d& initial_pose_estimate,
48  const sensor::PointCloud& point_cloud,
49  const HybridGrid& hybrid_grid,
50  transform::Rigid3d* pose_estimate) const;
51 
52  private:
53  std::vector<transform::Rigid3f> GenerateExhaustiveSearchTransforms(
54  float resolution, const sensor::PointCloud& point_cloud) const;
55  float ScoreCandidate(const HybridGrid& hybrid_grid,
56  const sensor::PointCloud& transformed_point_cloud,
57  const transform::Rigid3f& transform) const;
58 
59  const mapping_2d::scan_matching::proto::RealTimeCorrelativeScanMatcherOptions
61 };
62 
63 } // namespace scan_matching
64 } // namespace mapping_3d
65 } // namespace cartographer
66 
67 #endif // CARTOGRAPHER_MAPPING_3D_SCAN_MATCHING_REAL_TIME_CORRELATIVE_SCAN_MATCHER_H_
RealTimeCorrelativeScanMatcher & operator=(const RealTimeCorrelativeScanMatcher &)=delete
float ScoreCandidate(const HybridGrid &hybrid_grid, const sensor::PointCloud &transformed_point_cloud, const transform::Rigid3f &transform) const
const mapping_2d::scan_matching::proto::RealTimeCorrelativeScanMatcherOptions options_
std::vector< Eigen::Vector3f > PointCloud
Definition: point_cloud.h:30
std::vector< transform::Rigid3f > GenerateExhaustiveSearchTransforms(float resolution, const sensor::PointCloud &point_cloud) const
float Match(const transform::Rigid3d &initial_pose_estimate, const sensor::PointCloud &point_cloud, const HybridGrid &hybrid_grid, transform::Rigid3d *pose_estimate) const
RealTimeCorrelativeScanMatcher(const mapping_2d::scan_matching::proto::RealTimeCorrelativeScanMatcherOptions &options)


cartographer
Author(s):
autogenerated on Mon Jun 10 2019 12:51:39