Skip to content

Commit

Permalink
se3 expmap (#139)
Browse files Browse the repository at this point in the history
Co-authored-by: k.koide <[email protected]>
  • Loading branch information
koide3 and koide3 authored Nov 13, 2023
1 parent af0a772 commit 83454bd
Show file tree
Hide file tree
Showing 2 changed files with 30 additions and 7 deletions.
8 changes: 2 additions & 6 deletions include/fast_gicp/gicp/impl/lsq_registration_impl.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -111,9 +111,7 @@ bool LsqRegistration<PointTarget, PointSource>::step_gn(Eigen::Isometry3d& x0, E
Eigen::LDLT<Eigen::Matrix<double, 6, 6>> solver(H);
Eigen::Matrix<double, 6, 1> d = solver.solve(-b);

delta.setIdentity();
delta.linear() = so3_exp(d.head<3>()).toRotationMatrix();
delta.translation() = d.tail<3>();
delta = se3_exp(d);

x0 = delta * x0;
final_hessian_ = H;
Expand All @@ -136,9 +134,7 @@ bool LsqRegistration<PointTarget, PointSource>::step_lm(Eigen::Isometry3d& x0, E
Eigen::LDLT<Eigen::Matrix<double, 6, 6>> solver(H + lm_lambda_ * Eigen::Matrix<double, 6, 6>::Identity());
Eigen::Matrix<double, 6, 1> d = solver.solve(-b);

delta.setIdentity();
delta.linear() = so3_exp(d.head<3>()).toRotationMatrix();
delta.translation() = d.tail<3>();
delta = se3_exp(d);

Eigen::Isometry3d xi = delta * x0;
double yi = compute_error(xi);
Expand Down
29 changes: 28 additions & 1 deletion include/fast_gicp/so3/so3.hpp
Original file line number Diff line number Diff line change
Expand Up @@ -61,7 +61,7 @@ inline Eigen::Quaterniond so3_exp(const Eigen::Vector3d& omega) {
double theta;
double imag_factor;
double real_factor;
if(theta_sq < 1e-10) {
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;
Expand All @@ -76,6 +76,33 @@ inline Eigen::Quaterniond so3_exp(const Eigen::Vector3d& omega) {
return Eigen::Quaterniond(real_factor, imag_factor * omega.x(), imag_factor * omega.y(), imag_factor * omega.z());
}

// Rotation-first
inline Eigen::Isometry3d se3_exp(const Eigen::Matrix<double, 6, 1>& a) {
using std::cos;
using std::sin;
const Eigen::Vector3d omega = a.head<3>();

double theta = std::sqrt(omega.dot(omega));
const Eigen::Quaterniond so3 = so3_exp(omega);
const Eigen::Matrix3d Omega = skewd(omega);
const Eigen::Matrix3d Omega_sq = Omega * Omega;
Eigen::Matrix3d V;

if (theta < 1e-10) {
V = so3.matrix();
/// Note: That is an accurate expansion!
} else {
const double theta_sq = theta * theta;
V = (Eigen::Matrix3d::Identity() + (1.0 - cos(theta)) / (theta_sq)*Omega + (theta - sin(theta)) / (theta_sq * theta) * Omega_sq);
}

Eigen::Isometry3d se3 = Eigen::Isometry3d::Identity();
se3.linear() = so3.toRotationMatrix();
se3.translation() = V * a.tail<3>();

return se3;
}

} // namespace fast_gicp

#endif

0 comments on commit 83454bd

Please sign in to comment.