real_time_correlative_scan_matcher_3d.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_3D_SCAN_MATCHING_REAL_TIME_CORRELATIVE_SCAN_MATCHER_3D_H_
18 #define CARTOGRAPHER_MAPPING_INTERNAL_3D_SCAN_MATCHING_REAL_TIME_CORRELATIVE_SCAN_MATCHER_3D_H_
19 
20 #include <vector>
21 
22 #include "Eigen/Core"
24 #include "cartographer/mapping/proto/scan_matching/real_time_correlative_scan_matcher_options.pb.h"
26 
27 namespace cartographer {
28 namespace mapping {
29 namespace scan_matching {
30 
31 // A voxel accurate scan matcher, exhaustively evaluating the scan matching
32 // search space.
34  public:
36  const scan_matching::proto::RealTimeCorrelativeScanMatcherOptions&
37  options);
38 
40  delete;
42  const RealTimeCorrelativeScanMatcher3D&) = 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 proto::RealTimeCorrelativeScanMatcherOptions options_;
60 };
61 
62 } // namespace scan_matching
63 } // namespace mapping
64 } // namespace cartographer
65 
66 #endif // CARTOGRAPHER_MAPPING_INTERNAL_3D_SCAN_MATCHING_REAL_TIME_CORRELATIVE_SCAN_MATCHER_3D_H_
float Match(const transform::Rigid3d &initial_pose_estimate, const sensor::PointCloud &point_cloud, const HybridGrid &hybrid_grid, transform::Rigid3d *pose_estimate) const
float ScoreCandidate(const HybridGrid &hybrid_grid, const sensor::PointCloud &transformed_point_cloud, const transform::Rigid3f &transform) const
RealTimeCorrelativeScanMatcher3D(const scan_matching::proto::RealTimeCorrelativeScanMatcherOptions &options)
RealTimeCorrelativeScanMatcher3D & operator=(const RealTimeCorrelativeScanMatcher3D &)=delete
std::vector< Eigen::Vector3f > PointCloud
Definition: point_cloud.h:32
std::vector< transform::Rigid3f > GenerateExhaustiveSearchTransforms(float resolution, const sensor::PointCloud &point_cloud) const


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