rotation_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_ROTATION_DELTA_COST_FUNCTOR_2D_H_
18 #define CARTOGRAPHER_MAPPING_INTERNAL_2D_SCAN_MATCHING_ROTATION_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 rotating 'pose' to 'target_angle'. Cost increases with
28 // the solution's distance from 'target_angle'.
30  public:
31  static ceres::CostFunction* CreateAutoDiffCostFunction(
32  const double scaling_factor, const double target_angle) {
33  return new ceres::AutoDiffCostFunction<
34  RotationDeltaCostFunctor2D, 1 /* residuals */, 3 /* pose variables */>(
35  new RotationDeltaCostFunctor2D(scaling_factor, target_angle));
36  }
37 
38  template <typename T>
39  bool operator()(const T* const pose, T* residual) const {
40  residual[0] = scaling_factor_ * (pose[2] - angle_);
41  return true;
42  }
43 
44  private:
45  explicit RotationDeltaCostFunctor2D(const double scaling_factor,
46  const double target_angle)
47  : scaling_factor_(scaling_factor), angle_(target_angle) {}
48 
51  delete;
52 
53  const double scaling_factor_;
54  const double angle_;
55 };
56 
57 } // namespace scan_matching
58 } // namespace mapping
59 } // namespace cartographer
60 
61 #endif // CARTOGRAPHER_MAPPING_INTERNAL_2D_SCAN_MATCHING_ROTATION_DELTA_COST_FUNCTOR_2D_H_
RotationDeltaCostFunctor2D & operator=(const RotationDeltaCostFunctor2D &)=delete
static ceres::CostFunction * CreateAutoDiffCostFunction(const double scaling_factor, const double target_angle)
RotationDeltaCostFunctor2D(const double scaling_factor, const double target_angle)
transform::Rigid3d pose


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