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_ 21 #include "Eigen/Geometry" 22 #include "ceres/ceres.h" 31 const double scaling_factor,
32 const Eigen::Quaterniond& delta_rotation_imu_frame) {
33 return new ceres::AutoDiffCostFunction<
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],
49 const Eigen::Quaternion<T> error =
50 end.conjugate() * start * eigen_imu_calibration *
60 const Eigen::Quaterniond& delta_rotation_imu_frame)
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)
const Eigen::Quaterniond delta_rotation_imu_frame_
const double scaling_factor_
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