6 #include <Eigen/Geometry>
13 inline Eigen::Matrix3d
skew(
const Eigen::Vector3d& x) {
14 Eigen::Matrix3d
skew = Eigen::Matrix3d::Zero();
54 inline Eigen::Quaterniond
so3_exp(
const Eigen::Vector3d& omega) {
55 double theta_sq = omega.dot(omega);
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;
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);
70 return Eigen::Quaterniond(real_factor, imag_factor * omega.x(), imag_factor * omega.y(), imag_factor * omega.z());
77 inline Eigen::Isometry3d
se3_exp(
const Eigen::Matrix<double, 6, 1>& a) {
78 const Eigen::Vector3d omega = a.head<3>();
80 const double theta_sq = omega.dot(omega);
81 const double theta = std::sqrt(theta_sq);
83 Eigen::Isometry3d se3 = Eigen::Isometry3d::Identity();
84 se3.linear() =
so3_exp(omega).toRotationMatrix();
87 se3.translation() = se3.linear() * a.tail<3>();
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>();
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