acceleration_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_ACCELERATION_COST_FUNCTION_3D_H_
18 #define CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_ACCELERATION_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 accelerations.
29  public:
30  static ceres::CostFunction* CreateAutoDiffCostFunction(
31  const double scaling_factor,
32  const Eigen::Vector3d& delta_velocity_imu_frame,
33  const double first_delta_time_seconds,
34  const double second_delta_time_seconds) {
35  return new ceres::AutoDiffCostFunction<
36  AccelerationCostFunction3D, 3 /* residuals */,
37  4 /* rotation variables */, 3 /* position variables */,
38  3 /* position variables */, 3 /* position variables */,
39  1 /* gravity variables */, 4 /* rotation variables */>(
40  new AccelerationCostFunction3D(scaling_factor, delta_velocity_imu_frame,
41  first_delta_time_seconds,
42  second_delta_time_seconds));
43  }
44 
45  template <typename T>
46  bool operator()(const T* const middle_rotation, const T* const start_position,
47  const T* const middle_position, const T* const end_position,
48  const T* const gravity_constant,
49  const T* const imu_calibration, T* residual) const {
50  const Eigen::Quaternion<T> eigen_imu_calibration(
51  imu_calibration[0], imu_calibration[1], imu_calibration[2],
52  imu_calibration[3]);
53  const Eigen::Matrix<T, 3, 1> imu_delta_velocity =
54  ToEigen(middle_rotation) * eigen_imu_calibration *
55  delta_velocity_imu_frame_.cast<T>() -
56  *gravity_constant *
58  Eigen::Vector3d::UnitZ())
59  .cast<T>();
60  const Eigen::Matrix<T, 3, 1> start_velocity =
61  (Eigen::Map<const Eigen::Matrix<T, 3, 1>>(middle_position) -
62  Eigen::Map<const Eigen::Matrix<T, 3, 1>>(start_position)) /
64  const Eigen::Matrix<T, 3, 1> end_velocity =
65  (Eigen::Map<const Eigen::Matrix<T, 3, 1>>(end_position) -
66  Eigen::Map<const Eigen::Matrix<T, 3, 1>>(middle_position)) /
68  const Eigen::Matrix<T, 3, 1> delta_velocity = end_velocity - start_velocity;
69 
70  (Eigen::Map<Eigen::Matrix<T, 3, 1>>(residual) =
71  T(scaling_factor_) * (imu_delta_velocity - delta_velocity));
72  return true;
73  }
74 
75  private:
76  AccelerationCostFunction3D(const double scaling_factor,
77  const Eigen::Vector3d& delta_velocity_imu_frame,
78  const double first_delta_time_seconds,
79  const double second_delta_time_seconds)
80  : scaling_factor_(scaling_factor),
81  delta_velocity_imu_frame_(delta_velocity_imu_frame),
82  first_delta_time_seconds_(first_delta_time_seconds),
83  second_delta_time_seconds_(second_delta_time_seconds) {}
84 
87  delete;
88 
89  template <typename T>
90  static Eigen::Quaternion<T> ToEigen(const T* const quaternion) {
91  return Eigen::Quaternion<T>(quaternion[0], quaternion[1], quaternion[2],
92  quaternion[3]);
93  }
94 
95  const double scaling_factor_;
96  const Eigen::Vector3d delta_velocity_imu_frame_;
99 };
100 
101 } // namespace mapping
102 } // namespace cartographer
103 
104 #endif // CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_ACCELERATION_COST_FUNCTION_3D_H_
AccelerationCostFunction3D(const double scaling_factor, const Eigen::Vector3d &delta_velocity_imu_frame, const double first_delta_time_seconds, const double second_delta_time_seconds)
static Eigen::Quaternion< T > ToEigen(const T *const quaternion)
AccelerationCostFunction3D & operator=(const AccelerationCostFunction3D &)=delete
static ceres::CostFunction * CreateAutoDiffCostFunction(const double scaling_factor, const Eigen::Vector3d &delta_velocity_imu_frame, const double first_delta_time_seconds, const double second_delta_time_seconds)
bool operator()(const T *const middle_rotation, const T *const start_position, const T *const middle_position, const T *const end_position, const T *const gravity_constant, const T *const imu_calibration, T *residual) const


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