acceleration_cost_function_3d.h
Go to the documentation of this file.
00001 /*
00002  * Copyright 2016 The Cartographer Authors
00003  *
00004  * Licensed under the Apache License, Version 2.0 (the "License");
00005  * you may not use this file except in compliance with the License.
00006  * You may obtain a copy of the License at
00007  *
00008  *      http://www.apache.org/licenses/LICENSE-2.0
00009  *
00010  * Unless required by applicable law or agreed to in writing, software
00011  * distributed under the License is distributed on an "AS IS" BASIS,
00012  * WITHOUT WARRANTIES OR CONDITIONS OF ANY KIND, either express or implied.
00013  * See the License for the specific language governing permissions and
00014  * limitations under the License.
00015  */
00016 
00017 #ifndef CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_ACCELERATION_COST_FUNCTION_3D_H_
00018 #define CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_ACCELERATION_COST_FUNCTION_3D_H_
00019 
00020 #include "Eigen/Core"
00021 #include "Eigen/Geometry"
00022 #include "ceres/ceres.h"
00023 
00024 namespace cartographer {
00025 namespace mapping {
00026 
00027 // Penalizes differences between IMU data and optimized accelerations.
00028 class AccelerationCostFunction3D {
00029  public:
00030   static ceres::CostFunction* CreateAutoDiffCostFunction(
00031       const double scaling_factor,
00032       const Eigen::Vector3d& delta_velocity_imu_frame,
00033       const double first_delta_time_seconds,
00034       const double second_delta_time_seconds) {
00035     return new ceres::AutoDiffCostFunction<
00036         AccelerationCostFunction3D, 3 /* residuals */,
00037         4 /* rotation variables */, 3 /* position variables */,
00038         3 /* position variables */, 3 /* position variables */,
00039         1 /* gravity variables */, 4 /* rotation variables */>(
00040         new AccelerationCostFunction3D(scaling_factor, delta_velocity_imu_frame,
00041                                        first_delta_time_seconds,
00042                                        second_delta_time_seconds));
00043   }
00044 
00045   template <typename T>
00046   bool operator()(const T* const middle_rotation, const T* const start_position,
00047                   const T* const middle_position, const T* const end_position,
00048                   const T* const gravity_constant,
00049                   const T* const imu_calibration, T* residual) const {
00050     const Eigen::Quaternion<T> eigen_imu_calibration(
00051         imu_calibration[0], imu_calibration[1], imu_calibration[2],
00052         imu_calibration[3]);
00053     const Eigen::Matrix<T, 3, 1> imu_delta_velocity =
00054         ToEigen(middle_rotation) * eigen_imu_calibration *
00055             delta_velocity_imu_frame_.cast<T>() -
00056         *gravity_constant *
00057             (0.5 * (first_delta_time_seconds_ + second_delta_time_seconds_) *
00058              Eigen::Vector3d::UnitZ())
00059                 .cast<T>();
00060     const Eigen::Matrix<T, 3, 1> start_velocity =
00061         (Eigen::Map<const Eigen::Matrix<T, 3, 1>>(middle_position) -
00062          Eigen::Map<const Eigen::Matrix<T, 3, 1>>(start_position)) /
00063         T(first_delta_time_seconds_);
00064     const Eigen::Matrix<T, 3, 1> end_velocity =
00065         (Eigen::Map<const Eigen::Matrix<T, 3, 1>>(end_position) -
00066          Eigen::Map<const Eigen::Matrix<T, 3, 1>>(middle_position)) /
00067         T(second_delta_time_seconds_);
00068     const Eigen::Matrix<T, 3, 1> delta_velocity = end_velocity - start_velocity;
00069 
00070     (Eigen::Map<Eigen::Matrix<T, 3, 1>>(residual) =
00071          T(scaling_factor_) * (imu_delta_velocity - delta_velocity));
00072     return true;
00073   }
00074 
00075  private:
00076   AccelerationCostFunction3D(const double scaling_factor,
00077                              const Eigen::Vector3d& delta_velocity_imu_frame,
00078                              const double first_delta_time_seconds,
00079                              const double second_delta_time_seconds)
00080       : scaling_factor_(scaling_factor),
00081         delta_velocity_imu_frame_(delta_velocity_imu_frame),
00082         first_delta_time_seconds_(first_delta_time_seconds),
00083         second_delta_time_seconds_(second_delta_time_seconds) {}
00084 
00085   AccelerationCostFunction3D(const AccelerationCostFunction3D&) = delete;
00086   AccelerationCostFunction3D& operator=(const AccelerationCostFunction3D&) =
00087       delete;
00088 
00089   template <typename T>
00090   static Eigen::Quaternion<T> ToEigen(const T* const quaternion) {
00091     return Eigen::Quaternion<T>(quaternion[0], quaternion[1], quaternion[2],
00092                                 quaternion[3]);
00093   }
00094 
00095   const double scaling_factor_;
00096   const Eigen::Vector3d delta_velocity_imu_frame_;
00097   const double first_delta_time_seconds_;
00098   const double second_delta_time_seconds_;
00099 };
00100 
00101 }  // namespace mapping
00102 }  // namespace cartographer
00103 
00104 #endif  // CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_ACCELERATION_COST_FUNCTION_3D_H_


cartographer
Author(s): The Cartographer Authors
autogenerated on Thu May 9 2019 02:27:35