17 #ifndef CARTOGRAPHER_MAPPING_INTERNAL_3D_SCAN_MATCHING_ROTATION_DELTA_COST_FUNCTOR_3D_H_ 18 #define CARTOGRAPHER_MAPPING_INTERNAL_3D_SCAN_MATCHING_ROTATION_DELTA_COST_FUNCTOR_3D_H_ 24 #include "ceres/ceres.h" 25 #include "ceres/rotation.h" 29 namespace scan_matching {
36 const double scaling_factor,
const Eigen::Quaterniond& target_rotation) {
44 bool operator()(
const T*
const rotation_quaternion, T* residual)
const {
45 std::array<T, 4> delta;
60 const Eigen::Quaterniond& target_rotation)
80 #endif // CARTOGRAPHER_MAPPING_INTERNAL_3D_SCAN_MATCHING_ROTATION_DELTA_COST_FUNCTOR_3D_H_ RotationDeltaCostFunctor3D(const double scaling_factor, const Eigen::Quaterniond &target_rotation)
bool operator()(const T *const rotation_quaternion, T *residual) const
double target_rotation_inverse_[4]
RotationDeltaCostFunctor3D & operator=(const RotationDeltaCostFunctor3D &)=delete
void QuaternionProduct(const double *const z, const T *const w, T *const zw)
const double scaling_factor_
static ceres::CostFunction * CreateAutoDiffCostFunction(const double scaling_factor, const Eigen::Quaterniond &target_rotation)