translation_delta_cost_functor_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_TRANSLATION_DELTA_COST_FUNCTOR_2D_H_
18 #define CARTOGRAPHER_MAPPING_INTERNAL_2D_SCAN_MATCHING_TRANSLATION_DELTA_COST_FUNCTOR_2D_H_
19 
20 #include "Eigen/Core"
21 #include "ceres/ceres.h"
22 
23 namespace cartographer {
24 namespace mapping {
25 namespace scan_matching {
26 
27 // Computes the cost of translating 'pose' to 'target_translation'.
28 // Cost increases with the solution's distance from 'target_translation'.
30  public:
31  static ceres::CostFunction* CreateAutoDiffCostFunction(
32  const double scaling_factor, const Eigen::Vector2d& target_translation) {
33  return new ceres::AutoDiffCostFunction<TranslationDeltaCostFunctor2D,
34  2 /* residuals */,
35  3 /* pose variables */>(
36  new TranslationDeltaCostFunctor2D(scaling_factor, target_translation));
37  }
38 
39  template <typename T>
40  bool operator()(const T* const pose, T* residual) const {
41  residual[0] = scaling_factor_ * (pose[0] - x_);
42  residual[1] = scaling_factor_ * (pose[1] - y_);
43  return true;
44  }
45 
46  private:
47  // Constructs a new TranslationDeltaCostFunctor2D from the given
48  // 'target_translation' (x, y).
50  const double scaling_factor, const Eigen::Vector2d& target_translation)
51  : scaling_factor_(scaling_factor),
52  x_(target_translation.x()),
53  y_(target_translation.y()) {}
54 
57  const TranslationDeltaCostFunctor2D&) = delete;
58 
59  const double scaling_factor_;
60  const double x_;
61  const double y_;
62 };
63 
64 } // namespace scan_matching
65 } // namespace mapping
66 } // namespace cartographer
67 
68 #endif // CARTOGRAPHER_MAPPING_INTERNAL_2D_SCAN_MATCHING_TRANSLATION_DELTA_COST_FUNCTOR_2D_H_
static ceres::CostFunction * CreateAutoDiffCostFunction(const double scaling_factor, const Eigen::Vector2d &target_translation)
TranslationDeltaCostFunctor2D(const double scaling_factor, const Eigen::Vector2d &target_translation)
TranslationDeltaCostFunctor2D & operator=(const TranslationDeltaCostFunctor2D &)=delete
transform::Rigid3d pose


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