#ifndef FAST_GICP_SO3_HPP #define FAST_GICP_SO3_HPP #include #include namespace fast_gicp { inline Eigen::Matrix3f skew(const Eigen::Vector3f& x) { Eigen::Matrix3f skew = Eigen::Matrix3f::Zero(); skew(0, 1) = -x[2]; skew(0, 2) = x[1]; skew(1, 0) = x[2]; skew(1, 2) = -x[0]; skew(2, 0) = -x[1]; skew(2, 1) = x[0]; return skew; } inline Eigen::Matrix3d skewd(const Eigen::Vector3d& x) { Eigen::Matrix3d skew = Eigen::Matrix3d::Zero(); skew(0, 1) = -x[2]; skew(0, 2) = x[1]; skew(1, 0) = x[2]; skew(1, 2) = -x[0]; skew(2, 0) = -x[1]; skew(2, 1) = x[0]; return skew; } /* * SO3 expmap code taken from Sophus * https://github.com/strasdat/Sophus/blob/593db47500ea1a2de5f0e6579c86147991509c59/sophus/so3.hpp#L585 * * Copyright 2011-2017 Hauke Strasdat * 2012-2017 Steven Lovegrove * * Permission is hereby granted, free of charge, to any person obtaining a copy * of this software and associated documentation files (the "Software"), to * deal in the Software without restriction, including without limitation the * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or * sell copies of the Software, and to permit persons to whom the Software is * furnished to do so, subject to the following conditions: * * The above copyright notice and this permission notice shall be included in * all copies or substantial portions of the Software. * * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY, * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS * IN THE SOFTWARE. */ inline Eigen::Quaterniond so3_exp(const Eigen::Vector3d& omega) { double theta_sq = omega.dot(omega); double theta; double imag_factor; double real_factor; if(theta_sq < 1e-10) { theta = 0; double theta_quad = theta_sq * theta_sq; imag_factor = 0.5 - 1.0 / 48.0 * theta_sq + 1.0 / 3840.0 * theta_quad; real_factor = 1.0 - 1.0 / 8.0 * theta_sq + 1.0 / 384.0 * theta_quad; } else { theta = std::sqrt(theta_sq); double half_theta = 0.5 * theta; imag_factor = std::sin(half_theta) / theta; real_factor = std::cos(half_theta); } return Eigen::Quaterniond(real_factor, imag_factor * omega.x(), imag_factor * omega.y(), imag_factor * omega.z()); } } // namespace fast_gicp #endif