#ifndef MATH_H #define MATH_H #include #include // Sign function template T sgnFunc(T val) { return (T(0) < val) - (val < T(0)); } // Hat (skew) operator template inline Eigen::Matrix hat(const Eigen::Matrix &vec) { Eigen::Matrix mat; mat << 0, -vec(2), vec(1), vec(2), 0, -vec(0), -vec(1), vec(0), 0; return mat; } template static Eigen::Matrix skewSymmetric(const Eigen::MatrixBase &q) { Eigen::Matrix ans; ans << typename Derived::Scalar(0), -q(2), q(1), q(2), typename Derived::Scalar(0), -q(0), -q(1), q(0), typename Derived::Scalar(0); return ans; } template static Eigen::Matrix Qleft(const Eigen::QuaternionBase &q) { Eigen::Matrix ans; ans(0, 0) = q.w(), ans.template block<1, 3>(0, 1) = -q.vec().transpose(); ans.template block<3, 1>(1, 0) = q.vec(), ans.template block<3, 3>(1, 1) = q.w() * Eigen::Matrix::Identity() + skewSymmetric(q.vec()); return ans; } template static Eigen::Matrix Qright(const Eigen::QuaternionBase &p) { Eigen::Matrix ans; ans(0, 0) = p.w(), ans.template block<1, 3>(0, 1) = -p.vec().transpose(); ans.template block<3, 1>(1, 0) = p.vec(), ans.template block<3, 3>(1, 1) = p.w() * Eigen::Matrix::Identity() - skewSymmetric(p.vec()); return ans; } // Convert from quaternion to rotation vector template inline Eigen::Matrix quaternionToRotationVector(const Eigen::Quaternion &qua) { Eigen::Matrix mat = qua.toRotationMatrix(); Eigen::Matrix rotation_vec; Eigen::AngleAxis angle_axis; angle_axis.fromRotationMatrix(mat); rotation_vec = angle_axis.angle() * angle_axis.axis(); return rotation_vec; } // Right Jacobian matrix template inline Eigen::Matrix3d Jright(const Eigen::Quaternion &qua) { Eigen::Matrix mat; Eigen::Matrix rotation_vec = quaternionToRotationVector(qua); double theta_norm = rotation_vec.norm(); mat = Eigen::Matrix::Identity() - (1 - cos(theta_norm)) / (theta_norm * theta_norm + 1e-10) * hat(rotation_vec) + (theta_norm - sin(theta_norm)) / (theta_norm * theta_norm * theta_norm + 1e-10) * hat(rotation_vec) * hat(rotation_vec); return mat; } // Calculate the Jacobian with respect to the quaternion template inline Eigen::Matrix quaternionJacobian(const Eigen::Quaternion &qua, const Eigen::Matrix &vec) { Eigen::Matrix mat; Eigen::Matrix quaternion_imaginary(qua.x(), qua.y(), qua.z()); mat.template block<3, 1>(0, 0) = qua.w() * vec + quaternion_imaginary.cross(vec); mat.template block<3, 3>(0, 1) = quaternion_imaginary.dot(vec) * Eigen::Matrix::Identity() + quaternion_imaginary * vec.transpose() - vec * quaternion_imaginary.transpose() - qua.w() * hat(vec); return T(2) * mat; } // Calculate the Jacobian with respect to the inverse quaternion template inline Eigen::Matrix quaternionInvJacobian(const Eigen::Quaternion &qua, const Eigen::Matrix &vec) { Eigen::Matrix mat; Eigen::Matrix quaternion_imaginary(qua.x(), qua.y(), qua.z()); mat.template block<3, 1>(0, 0) = qua.w() * vec + vec.cross(quaternion_imaginary); mat.template block<3, 3>(0, 1) = quaternion_imaginary.dot(vec) * Eigen::Matrix::Identity() + quaternion_imaginary * vec.transpose() - vec * quaternion_imaginary.transpose() + qua.w() * hat(vec); return T(2) * mat; } // Calculate the Jacobian rotation vector to quaternion template inline Eigen::Matrix JacobianV2Q(const Eigen::Quaternion &qua) { Eigen::Matrix mat; T c = 1 / (1 - qua.w() * qua.w()); T d = acos(qua.w()) / sqrt(1 - qua.w() * qua.w()); mat.template block<3, 1>(0, 0) = Eigen::Matrix(c * qua.x() * (d * qua.x() - 1), c * qua.y() * (d * qua.x() - 1), c * qua.z() * (d * qua.x() - 1)); mat.template block<3, 3>(0, 1) = d * Eigen::Matrix::Identity(); return T(2) * mat; } //get quaternion from rotation vector template Eigen::Quaternion deltaQ(const Eigen::MatrixBase &theta) { typedef typename Derived::Scalar Scalar_t; Eigen::Quaternion dq; Eigen::Matrix half_theta = theta; half_theta /= static_cast(2.0); dq.w() = static_cast(1.0); dq.x() = half_theta.x(); dq.y() = half_theta.y(); dq.z() = half_theta.z(); return dq; } template inline Eigen::Matrix LeftQuatMatrix(const Eigen::QuaternionBase &q) { Eigen::Matrix m; Eigen::Matrix vq = q.vec(); typename Derived::Scalar q4 = q.w(); m.block(0, 0, 3, 3) << q4 * Eigen::Matrix3d::Identity() + skewSymmetric(vq); m.block(3, 0, 1, 3) << -vq.transpose(); m.block(0, 3, 3, 1) << vq; m(3, 3) = q4; return m; } template inline Eigen::Matrix RightQuatMatrix(const Eigen::QuaternionBase &p) { Eigen::Matrix m; Eigen::Matrix vp = p.vec(); typename Derived::Scalar p4 = p.w(); m.block(0, 0, 3, 3) << p4 * Eigen::Matrix3d::Identity() - skewSymmetric(vp); m.block(3, 0, 1, 3) << -vp.transpose(); m.block(0, 3, 3, 1) << vp; m(3, 3) = p4; return m; } template Eigen::Quaternion unifyQuaternion(const Eigen::Quaternion &q) { if(q.w() >= 0) return q; else { Eigen::Quaternion resultQ(-q.w(), -q.x(), -q.y(), -q.z()); return resultQ; } } #endif // MATH_UTILS_H