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


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