mapping_3d/scan_matching/ceres_scan_matcher.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 <string>
20 #include <utility>
21 #include <vector>
22 
31 #include "ceres/ceres.h"
32 #include "glog/logging.h"
33 
34 namespace cartographer {
35 namespace mapping_3d {
36 namespace scan_matching {
37 namespace {
38 
39 struct YawOnlyQuaternionPlus {
40  template <typename T>
41  bool operator()(const T* x, const T* delta, T* x_plus_delta) const {
42  const T clamped_delta = common::Clamp(delta[0], T(-0.5), T(0.5));
43  T q_delta[4];
44  q_delta[0] = ceres::sqrt(1. - clamped_delta * clamped_delta);
45  q_delta[1] = T(0.);
46  q_delta[2] = T(0.);
47  q_delta[3] = clamped_delta;
48  ceres::QuaternionProduct(q_delta, x, x_plus_delta);
49  return true;
50  }
51 };
52 
53 } // namespace
54 
55 proto::CeresScanMatcherOptions CreateCeresScanMatcherOptions(
56  common::LuaParameterDictionary* const parameter_dictionary) {
57  proto::CeresScanMatcherOptions options;
58  for (int i = 0;; ++i) {
59  const string lua_identifier = "occupied_space_weight_" + std::to_string(i);
60  if (!parameter_dictionary->HasKey(lua_identifier)) {
61  break;
62  }
63  options.add_occupied_space_weight(
64  parameter_dictionary->GetDouble(lua_identifier));
65  }
66  options.set_translation_weight(
67  parameter_dictionary->GetDouble("translation_weight"));
68  options.set_rotation_weight(
69  parameter_dictionary->GetDouble("rotation_weight"));
70  options.set_only_optimize_yaw(
71  parameter_dictionary->GetBool("only_optimize_yaw"));
72  *options.mutable_ceres_solver_options() =
74  parameter_dictionary->GetDictionary("ceres_solver_options").get());
75  return options;
76 }
77 
79  const proto::CeresScanMatcherOptions& options)
80  : options_(options),
81  ceres_solver_options_(
82  common::CreateCeresSolverOptions(options.ceres_solver_options())) {
83  ceres_solver_options_.linear_solver_type = ceres::DENSE_QR;
84 }
85 
86 void CeresScanMatcher::Match(const transform::Rigid3d& previous_pose,
87  const transform::Rigid3d& initial_pose_estimate,
88  const std::vector<PointCloudAndHybridGridPointers>&
89  point_clouds_and_hybrid_grids,
90  transform::Rigid3d* const pose_estimate,
91  ceres::Solver::Summary* const summary) {
92  ceres::Problem problem;
93  CeresPose ceres_pose(
94  initial_pose_estimate, nullptr /* translation_parameterization */,
95  options_.only_optimize_yaw()
96  ? std::unique_ptr<ceres::LocalParameterization>(
97  common::make_unique<ceres::AutoDiffLocalParameterization<
98  YawOnlyQuaternionPlus, 4, 1>>())
99  : std::unique_ptr<ceres::LocalParameterization>(
100  common::make_unique<ceres::QuaternionParameterization>()),
101  &problem);
102 
103  CHECK_EQ(options_.occupied_space_weight_size(),
104  point_clouds_and_hybrid_grids.size());
105  for (size_t i = 0; i != point_clouds_and_hybrid_grids.size(); ++i) {
106  CHECK_GT(options_.occupied_space_weight(i), 0.);
107  const sensor::PointCloud& point_cloud =
108  *point_clouds_and_hybrid_grids[i].first;
109  const HybridGrid& hybrid_grid = *point_clouds_and_hybrid_grids[i].second;
110  problem.AddResidualBlock(
111  new ceres::AutoDiffCostFunction<OccupiedSpaceCostFunctor,
112  ceres::DYNAMIC, 3, 4>(
114  options_.occupied_space_weight(i) /
115  std::sqrt(static_cast<double>(point_cloud.size())),
116  point_cloud, hybrid_grid),
117  point_cloud.size()),
118  nullptr, ceres_pose.translation(), ceres_pose.rotation());
119  }
120  CHECK_GT(options_.translation_weight(), 0.);
121  problem.AddResidualBlock(
122  new ceres::AutoDiffCostFunction<TranslationDeltaCostFunctor, 3, 3>(
123  new TranslationDeltaCostFunctor(options_.translation_weight(),
124  previous_pose)),
125  nullptr, ceres_pose.translation());
126  CHECK_GT(options_.rotation_weight(), 0.);
127  problem.AddResidualBlock(
128  new ceres::AutoDiffCostFunction<RotationDeltaCostFunctor, 3, 4>(
129  new RotationDeltaCostFunctor(options_.rotation_weight(),
130  initial_pose_estimate.rotation())),
131  nullptr, ceres_pose.rotation());
132 
133  ceres::Solve(ceres_solver_options_, &problem, summary);
134 
135  *pose_estimate = ceres_pose.ToRigid();
136 }
137 
138 } // namespace scan_matching
139 } // namespace mapping_3d
140 } // namespace cartographer
proto::RangeDataInserterOptions options_
const Quaternion & rotation() const
void Match(const transform::Rigid3d &previous_pose, const transform::Rigid3d &initial_pose_estimate, const std::vector< PointCloudAndHybridGridPointers > &point_clouds_and_hybrid_grids, transform::Rigid3d *pose_estimate, ceres::Solver::Summary *summary)
proto::CeresScanMatcherOptions CreateCeresScanMatcherOptions(common::LuaParameterDictionary *const parameter_dictionary)
ceres::Solver::Options CreateCeresSolverOptions(const proto::CeresSolverOptions &proto)
std::vector< Eigen::Vector3f > PointCloud
Definition: point_cloud.h:30
proto::CeresSolverOptions CreateCeresSolverOptionsProto(common::LuaParameterDictionary *parameter_dictionary)
T Clamp(const T value, const T min, const T max)
Definition: math.h:32
std::unique_ptr< LuaParameterDictionary > GetDictionary(const string &key)
_Unique_if< T >::_Single_object make_unique(Args &&...args)
Definition: make_unique.h:46


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