rotation_delta_cost_functor_3d.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_3D_SCAN_MATCHING_ROTATION_DELTA_COST_FUNCTOR_3D_H_
18 #define CARTOGRAPHER_MAPPING_INTERNAL_3D_SCAN_MATCHING_ROTATION_DELTA_COST_FUNCTOR_3D_H_
19 
20 #include <cmath>
21 
22 #include "Eigen/Core"
24 #include "ceres/ceres.h"
25 #include "ceres/rotation.h"
26 
27 namespace cartographer {
28 namespace mapping {
29 namespace scan_matching {
30 
31 // Computes the cost of rotating 'rotation_quaternion' to 'target_rotation'.
32 // Cost increases with the solution's distance from 'target_rotation'.
34  public:
35  static ceres::CostFunction* CreateAutoDiffCostFunction(
36  const double scaling_factor, const Eigen::Quaterniond& target_rotation) {
37  return new ceres::AutoDiffCostFunction<RotationDeltaCostFunctor3D,
38  3 /* residuals */,
39  4 /* rotation variables */>(
40  new RotationDeltaCostFunctor3D(scaling_factor, target_rotation));
41  }
42 
43  template <typename T>
44  bool operator()(const T* const rotation_quaternion, T* residual) const {
45  std::array<T, 4> delta;
47  delta.data());
48  // Will compute the squared norm of the imaginary component of the delta
49  // quaternion which is sin(phi/2)^2.
50  residual[0] = scaling_factor_ * delta[1];
51  residual[1] = scaling_factor_ * delta[2];
52  residual[2] = scaling_factor_ * delta[3];
53  return true;
54  }
55 
56  private:
57  // Constructs a new RotationDeltaCostFunctor3D from the given
58  // 'target_rotation'.
59  explicit RotationDeltaCostFunctor3D(const double scaling_factor,
60  const Eigen::Quaterniond& target_rotation)
61  : scaling_factor_(scaling_factor) {
62  target_rotation_inverse_[0] = target_rotation.w();
63  target_rotation_inverse_[1] = -target_rotation.x();
64  target_rotation_inverse_[2] = -target_rotation.y();
65  target_rotation_inverse_[3] = -target_rotation.z();
66  }
67 
70  delete;
71 
72  const double scaling_factor_;
74 };
75 
76 } // namespace scan_matching
77 } // namespace mapping
78 } // namespace cartographer
79 
80 #endif // CARTOGRAPHER_MAPPING_INTERNAL_3D_SCAN_MATCHING_ROTATION_DELTA_COST_FUNCTOR_3D_H_
RotationDeltaCostFunctor3D(const double scaling_factor, const Eigen::Quaterniond &target_rotation)
bool operator()(const T *const rotation_quaternion, T *residual) const
RotationDeltaCostFunctor3D & operator=(const RotationDeltaCostFunctor3D &)=delete
void QuaternionProduct(const double *const z, const T *const w, T *const zw)
Definition: math.h:75
static ceres::CostFunction * CreateAutoDiffCostFunction(const double scaling_factor, const Eigen::Quaterniond &target_rotation)


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