ceres_scan_matcher_2d.cc
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 
18 
19 #include <utility>
20 #include <vector>
21 
22 #include "Eigen/Core"
30 #include "ceres/ceres.h"
31 #include "glog/logging.h"
32 
33 namespace cartographer {
34 namespace mapping {
35 namespace scan_matching {
36 
37 proto::CeresScanMatcherOptions2D CreateCeresScanMatcherOptions2D(
38  common::LuaParameterDictionary* const parameter_dictionary) {
39  proto::CeresScanMatcherOptions2D options;
40  options.set_occupied_space_weight(
41  parameter_dictionary->GetDouble("occupied_space_weight"));
42  options.set_translation_weight(
43  parameter_dictionary->GetDouble("translation_weight"));
44  options.set_rotation_weight(
45  parameter_dictionary->GetDouble("rotation_weight"));
46  *options.mutable_ceres_solver_options() =
48  parameter_dictionary->GetDictionary("ceres_solver_options").get());
49  return options;
50 }
51 
53  const proto::CeresScanMatcherOptions2D& options)
54  : options_(options),
55  ceres_solver_options_(
56  common::CreateCeresSolverOptions(options.ceres_solver_options())) {
57  ceres_solver_options_.linear_solver_type = ceres::DENSE_QR;
58 }
59 
61 
62 void CeresScanMatcher2D::Match(const Eigen::Vector2d& target_translation,
63  const transform::Rigid2d& initial_pose_estimate,
64  const sensor::PointCloud& point_cloud,
65  const Grid2D& grid,
66  transform::Rigid2d* const pose_estimate,
67  ceres::Solver::Summary* const summary) const {
68  double ceres_pose_estimate[3] = {initial_pose_estimate.translation().x(),
69  initial_pose_estimate.translation().y(),
70  initial_pose_estimate.rotation().angle()};
71  ceres::Problem problem;
72  CHECK_GT(options_.occupied_space_weight(), 0.);
73  problem.AddResidualBlock(
75  options_.occupied_space_weight() /
76  std::sqrt(static_cast<double>(point_cloud.size())),
77  point_cloud, grid),
78  nullptr /* loss function */, ceres_pose_estimate);
79  CHECK_GT(options_.translation_weight(), 0.);
80  problem.AddResidualBlock(
82  options_.translation_weight(), target_translation),
83  nullptr /* loss function */, ceres_pose_estimate);
84  CHECK_GT(options_.rotation_weight(), 0.);
85  problem.AddResidualBlock(
87  options_.rotation_weight(), ceres_pose_estimate[2]),
88  nullptr /* loss function */, ceres_pose_estimate);
89 
90  ceres::Solve(ceres_solver_options_, &problem, summary);
91 
92  *pose_estimate = transform::Rigid2d(
93  {ceres_pose_estimate[0], ceres_pose_estimate[1]}, ceres_pose_estimate[2]);
94 }
95 
96 } // namespace scan_matching
97 } // namespace mapping
98 } // namespace cartographer
static ceres::CostFunction * CreateAutoDiffCostFunction(const double scaling_factor, const sensor::PointCloud &point_cloud, const Grid2D &grid)
static ceres::CostFunction * CreateAutoDiffCostFunction(const double scaling_factor, const Eigen::Vector2d &target_translation)
Rigid2< double > Rigid2d
proto::CeresScanMatcherOptions2D CreateCeresScanMatcherOptions2D(common::LuaParameterDictionary *const parameter_dictionary)
proto::ProbabilityGridRangeDataInserterOptions2D options_
CeresScanMatcher2D(const proto::CeresScanMatcherOptions2D &options)
ceres::Solver::Options CreateCeresSolverOptions(const proto::CeresSolverOptions &proto)
std::vector< Eigen::Vector3f > PointCloud
Definition: point_cloud.h:32
const Vector & translation() const
static ceres::CostFunction * CreateAutoDiffCostFunction(const double scaling_factor, const double target_angle)
std::unique_ptr< LuaParameterDictionary > GetDictionary(const std::string &key)
proto::CeresSolverOptions CreateCeresSolverOptionsProto(common::LuaParameterDictionary *parameter_dictionary)
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


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