rotation_cost_function_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_OPTIMIZATION_COST_FUNCTIONS_ROTATION_COST_FUNCTION_3D_H_
18 #define CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_ROTATION_COST_FUNCTION_3D_H_
19 
20 #include "Eigen/Core"
21 #include "Eigen/Geometry"
22 #include "ceres/ceres.h"
23 
24 namespace cartographer {
25 namespace mapping {
26 
27 // Penalizes differences between IMU data and optimized orientations.
29  public:
30  static ceres::CostFunction* CreateAutoDiffCostFunction(
31  const double scaling_factor,
32  const Eigen::Quaterniond& delta_rotation_imu_frame) {
33  return new ceres::AutoDiffCostFunction<
34  RotationCostFunction3D, 3 /* residuals */, 4 /* rotation variables */,
35  4 /* rotation variables */, 4 /* rotation variables */
36  >(new RotationCostFunction3D(scaling_factor, delta_rotation_imu_frame));
37  }
38 
39  template <typename T>
40  bool operator()(const T* const start_rotation, const T* const end_rotation,
41  const T* const imu_calibration, T* residual) const {
42  const Eigen::Quaternion<T> start(start_rotation[0], start_rotation[1],
43  start_rotation[2], start_rotation[3]);
44  const Eigen::Quaternion<T> end(end_rotation[0], end_rotation[1],
45  end_rotation[2], end_rotation[3]);
46  const Eigen::Quaternion<T> eigen_imu_calibration(
47  imu_calibration[0], imu_calibration[1], imu_calibration[2],
48  imu_calibration[3]);
49  const Eigen::Quaternion<T> error =
50  end.conjugate() * start * eigen_imu_calibration *
51  delta_rotation_imu_frame_.cast<T>() * eigen_imu_calibration.conjugate();
52  residual[0] = scaling_factor_ * error.x();
53  residual[1] = scaling_factor_ * error.y();
54  residual[2] = scaling_factor_ * error.z();
55  return true;
56  }
57 
58  private:
59  RotationCostFunction3D(const double scaling_factor,
60  const Eigen::Quaterniond& delta_rotation_imu_frame)
61  : scaling_factor_(scaling_factor),
62  delta_rotation_imu_frame_(delta_rotation_imu_frame) {}
63 
66 
67  const double scaling_factor_;
68  const Eigen::Quaterniond delta_rotation_imu_frame_;
69 };
70 
71 } // namespace mapping
72 } // namespace cartographer
73 
74 #endif // CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_ROTATION_COST_FUNCTION_3D_H_
static ceres::CostFunction * CreateAutoDiffCostFunction(const double scaling_factor, const Eigen::Quaterniond &delta_rotation_imu_frame)
RotationCostFunction3D(const double scaling_factor, const Eigen::Quaterniond &delta_rotation_imu_frame)
bool operator()(const T *const start_rotation, const T *const end_rotation, const T *const imu_calibration, T *residual) const
RotationCostFunction3D & operator=(const RotationCostFunction3D &)=delete


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