mapping_3d/scan_matching/rotation_delta_cost_functor.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_3D_SCAN_MATCHING_ROTATION_DELTA_COST_FUNCTOR_H_
18 #define CARTOGRAPHER_MAPPING_3D_SCAN_MATCHING_ROTATION_DELTA_COST_FUNCTOR_H_
19 
20 #include <cmath>
21 
22 #include "Eigen/Core"
25 #include "ceres/rotation.h"
26 
27 namespace cartographer {
28 namespace mapping_3d {
29 namespace scan_matching {
30 
31 // Computes the cost of rotating the pose estimate. Cost increases with the
32 // solution's distance from the rotation estimate.
34  public:
35  // Constructs a new RotationDeltaCostFunctor from the given
36  // 'rotation_estimate'.
37  explicit RotationDeltaCostFunctor(const double scaling_factor,
38  const Eigen::Quaterniond& initial_rotation)
39  : scaling_factor_(scaling_factor) {
40  initial_rotation_inverse_[0] = initial_rotation.w();
41  initial_rotation_inverse_[1] = -initial_rotation.x();
42  initial_rotation_inverse_[2] = -initial_rotation.y();
43  initial_rotation_inverse_[3] = -initial_rotation.z();
44  }
45 
48 
49  template <typename T>
50  bool operator()(const T* const rotation_quaternion, T* residual) const {
51  T delta[4];
52  T initial_rotation_inverse[4] = {
55  ceres::QuaternionProduct(initial_rotation_inverse, rotation_quaternion,
56  delta);
57  // Will compute the squared norm of the imaginary component of the delta
58  // quaternion which is sin(phi/2)^2.
59  residual[0] = scaling_factor_ * delta[1];
60  residual[1] = scaling_factor_ * delta[2];
61  residual[2] = scaling_factor_ * delta[3];
62  return true;
63  }
64 
65  private:
66  const double scaling_factor_;
68 };
69 
70 } // namespace scan_matching
71 } // namespace mapping_3d
72 } // namespace cartographer
73 
74 #endif // CARTOGRAPHER_MAPPING_3D_SCAN_MATCHING_ROTATION_DELTA_COST_FUNCTOR_H_
RotationDeltaCostFunctor(const double scaling_factor, const Eigen::Quaterniond &initial_rotation)
RotationDeltaCostFunctor & operator=(const RotationDeltaCostFunctor &)=delete


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