17 #ifndef CARTOGRAPHER_MAPPING_3D_SCAN_MATCHING_ROTATION_DELTA_COST_FUNCTOR_H_ 18 #define CARTOGRAPHER_MAPPING_3D_SCAN_MATCHING_ROTATION_DELTA_COST_FUNCTOR_H_ 25 #include "ceres/rotation.h" 28 namespace mapping_3d {
29 namespace scan_matching {
38 const Eigen::Quaterniond& initial_rotation)
50 bool operator()(
const T*
const rotation_quaternion, T* residual)
const {
52 T initial_rotation_inverse[4] = {
55 ceres::QuaternionProduct(initial_rotation_inverse, rotation_quaternion,
74 #endif // CARTOGRAPHER_MAPPING_3D_SCAN_MATCHING_ROTATION_DELTA_COST_FUNCTOR_H_ RotationDeltaCostFunctor(const double scaling_factor, const Eigen::Quaterniond &initial_rotation)
double initial_rotation_inverse_[4]
RotationDeltaCostFunctor & operator=(const RotationDeltaCostFunctor &)=delete
bool operator()(const T *const rotation_quaternion, T *residual) const
const double scaling_factor_