ceres_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_CERES_SCAN_MATCHER_2D_H_
18 #define CARTOGRAPHER_MAPPING_INTERNAL_2D_SCAN_MATCHING_CERES_SCAN_MATCHER_2D_H_
19 
20 #include <memory>
21 #include <vector>
22 
23 #include "Eigen/Core"
26 #include "cartographer/mapping/proto/scan_matching/ceres_scan_matcher_options_2d.pb.h"
28 #include "ceres/ceres.h"
29 
30 namespace cartographer {
31 namespace mapping {
32 namespace scan_matching {
33 
34 proto::CeresScanMatcherOptions2D CreateCeresScanMatcherOptions2D(
35  common::LuaParameterDictionary* parameter_dictionary);
36 
37 // Align scans with an existing map using Ceres.
39  public:
40  explicit CeresScanMatcher2D(const proto::CeresScanMatcherOptions2D& options);
41  virtual ~CeresScanMatcher2D();
42 
43  CeresScanMatcher2D(const CeresScanMatcher2D&) = delete;
45 
46  // Aligns 'point_cloud' within the 'grid' given an
47  // 'initial_pose_estimate' and returns a 'pose_estimate' and the solver
48  // 'summary'.
49  void Match(const Eigen::Vector2d& target_translation,
50  const transform::Rigid2d& initial_pose_estimate,
51  const sensor::PointCloud& point_cloud, const Grid2D& grid,
52  transform::Rigid2d* pose_estimate,
53  ceres::Solver::Summary* summary) const;
54 
55  private:
56  const proto::CeresScanMatcherOptions2D options_;
57  ceres::Solver::Options ceres_solver_options_;
58 };
59 
60 } // namespace scan_matching
61 } // namespace mapping
62 } // namespace cartographer
63 
64 #endif // CARTOGRAPHER_MAPPING_INTERNAL_2D_SCAN_MATCHING_CERES_SCAN_MATCHER_2D_H_
proto::CeresScanMatcherOptions2D CreateCeresScanMatcherOptions2D(common::LuaParameterDictionary *const parameter_dictionary)
CeresScanMatcher2D(const proto::CeresScanMatcherOptions2D &options)
std::vector< Eigen::Vector3f > PointCloud
Definition: point_cloud.h:32
void Match(const Eigen::Vector2d &target_translation, const transform::Rigid2d &initial_pose_estimate, const sensor::PointCloud &point_cloud, const Grid2D &grid, transform::Rigid2d *pose_estimate, ceres::Solver::Summary *summary) const
CeresScanMatcher2D & operator=(const CeresScanMatcher2D &)=delete


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