rotation_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_ROTATION_COST_FUNCTION_3D_H_
00018 #define CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_ROTATION_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 orientations.
00028 class RotationCostFunction3D {
00029  public:
00030   static ceres::CostFunction* CreateAutoDiffCostFunction(
00031       const double scaling_factor,
00032       const Eigen::Quaterniond& delta_rotation_imu_frame) {
00033     return new ceres::AutoDiffCostFunction<
00034         RotationCostFunction3D, 3 /* residuals */, 4 /* rotation variables */,
00035         4 /* rotation variables */, 4 /* rotation variables */
00036         >(new RotationCostFunction3D(scaling_factor, delta_rotation_imu_frame));
00037   }
00038 
00039   template <typename T>
00040   bool operator()(const T* const start_rotation, const T* const end_rotation,
00041                   const T* const imu_calibration, T* residual) const {
00042     const Eigen::Quaternion<T> start(start_rotation[0], start_rotation[1],
00043                                      start_rotation[2], start_rotation[3]);
00044     const Eigen::Quaternion<T> end(end_rotation[0], end_rotation[1],
00045                                    end_rotation[2], end_rotation[3]);
00046     const Eigen::Quaternion<T> eigen_imu_calibration(
00047         imu_calibration[0], imu_calibration[1], imu_calibration[2],
00048         imu_calibration[3]);
00049     const Eigen::Quaternion<T> error =
00050         end.conjugate() * start * eigen_imu_calibration *
00051         delta_rotation_imu_frame_.cast<T>() * eigen_imu_calibration.conjugate();
00052     residual[0] = scaling_factor_ * error.x();
00053     residual[1] = scaling_factor_ * error.y();
00054     residual[2] = scaling_factor_ * error.z();
00055     return true;
00056   }
00057 
00058  private:
00059   RotationCostFunction3D(const double scaling_factor,
00060                          const Eigen::Quaterniond& delta_rotation_imu_frame)
00061       : scaling_factor_(scaling_factor),
00062         delta_rotation_imu_frame_(delta_rotation_imu_frame) {}
00063 
00064   RotationCostFunction3D(const RotationCostFunction3D&) = delete;
00065   RotationCostFunction3D& operator=(const RotationCostFunction3D&) = delete;
00066 
00067   const double scaling_factor_;
00068   const Eigen::Quaterniond delta_rotation_imu_frame_;
00069 };
00070 
00071 }  // namespace mapping
00072 }  // namespace cartographer
00073 
00074 #endif  // CARTOGRAPHER_MAPPING_INTERNAL_OPTIMIZATION_COST_FUNCTIONS_ROTATION_COST_FUNCTION_3D_H_


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