small_gicp
lie.hpp
Go to the documentation of this file.
1 // SPDX-FileCopyrightText: Copyright 2024 Kenji Koide
2 // SPDX-License-Identifier: MIT
3 #pragma once
4 
5 #include <Eigen/Core>
6 #include <Eigen/Geometry>
7 
8 namespace small_gicp {
9 
13 inline Eigen::Matrix3d skew(const Eigen::Vector3d& x) {
14  Eigen::Matrix3d skew = Eigen::Matrix3d::Zero();
15  skew(0, 1) = -x[2];
16  skew(0, 2) = x[1];
17  skew(1, 0) = x[2];
18  skew(1, 2) = -x[0];
19  skew(2, 0) = -x[1];
20  skew(2, 1) = x[0];
21 
22  return skew;
23 }
24 
25 /*
26  * SO3 expmap code taken from Sophus
27  * https://github.com/strasdat/Sophus/blob/593db47500ea1a2de5f0e6579c86147991509c59/sophus/so3.hpp#L585
28  *
29  * Copyright 2011-2017 Hauke Strasdat
30  * 2012-2017 Steven Lovegrove
31  *
32  * Permission is hereby granted, free of charge, to any person obtaining a copy
33  * of this software and associated documentation files (the "Software"), to
34  * deal in the Software without restriction, including without limitation the
35  * rights to use, copy, modify, merge, publish, distribute, sublicense, and/or
36  * sell copies of the Software, and to permit persons to whom the Software is
37  * furnished to do so, subject to the following conditions:
38  *
39  * The above copyright notice and this permission notice shall be included in
40  * all copies or substantial portions of the Software.
41  *
42  * THE SOFTWARE IS PROVIDED "AS IS", WITHOUT WARRANTY OF ANY KIND, EXPRESS OR
43  * IMPLIED, INCLUDING BUT NOT LIMITED TO THE WARRANTIES OF MERCHANTABILITY,
44  * FITNESS FOR A PARTICULAR PURPOSE AND NONINFRINGEMENT. IN NO EVENT SHALL THE
45  * AUTHORS OR COPYRIGHT HOLDERS BE LIABLE FOR ANY CLAIM, DAMAGES OR OTHER
46  * LIABILITY, WHETHER IN AN ACTION OF CONTRACT, TORT OR OTHERWISE, ARISING
47  * FROM, OUT OF OR IN CONNECTION WITH THE SOFTWARE OR THE USE OR OTHER DEALINGS
48  * IN THE SOFTWARE.
49  */
50 
54 inline Eigen::Quaterniond so3_exp(const Eigen::Vector3d& omega) {
55  double theta_sq = omega.dot(omega);
56 
57  double imag_factor;
58  double real_factor;
59  if (theta_sq < 1e-10) {
60  double theta_quad = theta_sq * theta_sq;
61  imag_factor = 0.5 - 1.0 / 48.0 * theta_sq + 1.0 / 3840.0 * theta_quad;
62  real_factor = 1.0 - 1.0 / 8.0 * theta_sq + 1.0 / 384.0 * theta_quad;
63  } else {
64  double theta = std::sqrt(theta_sq);
65  double half_theta = 0.5 * theta;
66  imag_factor = std::sin(half_theta) / theta;
67  real_factor = std::cos(half_theta);
68  }
69 
70  return Eigen::Quaterniond(real_factor, imag_factor * omega.x(), imag_factor * omega.y(), imag_factor * omega.z());
71 }
72 
73 // Rotation-first
77 inline Eigen::Isometry3d se3_exp(const Eigen::Matrix<double, 6, 1>& a) {
78  const Eigen::Vector3d omega = a.head<3>();
79 
80  const double theta_sq = omega.dot(omega);
81  const double theta = std::sqrt(theta_sq);
82 
83  Eigen::Isometry3d se3 = Eigen::Isometry3d::Identity();
84  se3.linear() = so3_exp(omega).toRotationMatrix();
85 
86  if (theta < 1e-10) {
87  se3.translation() = se3.linear() * a.tail<3>();
89  } else {
90  const Eigen::Matrix3d Omega = skew(omega);
91  const Eigen::Matrix3d V = (Eigen::Matrix3d::Identity() + (1.0 - std::cos(theta)) / theta_sq * Omega + (theta - std::sin(theta)) / (theta_sq * theta) * Omega * Omega);
92  se3.translation() = V * a.tail<3>();
93  }
94 
95  return se3;
96 }
97 
98 } // namespace small_gicp
Definition: flat_container.hpp:12
Eigen::Isometry3d se3_exp(const Eigen::Matrix< double, 6, 1 > &a)
SE3 expmap (Rotation-first).
Definition: lie.hpp:77
Eigen::Quaterniond so3_exp(const Eigen::Vector3d &omega)
SO3 expmap.
Definition: lie.hpp:54
Eigen::Matrix3d skew(const Eigen::Vector3d &x)
Create skew symmetric matrix.
Definition: lie.hpp:13