27#ifndef G2O_ISOMETRY3D_MAPPINGS_H_
28#define G2O_ISOMETRY3D_MAPPINGS_H_
56 return A.matrix().topLeftCorner<3, 3>();
65template <
typename Derived>
67 Eigen::JacobiSVD<Matrix3> svd(R, Eigen::ComputeFullU | Eigen::ComputeFullV);
68 double det = (svd.matrixU() * svd.matrixV().adjoint()).determinant();
70 scaledU.col(0) /= det;
71 const_cast<Eigen::MatrixBase<Derived>&
>(R) =
72 scaledU * svd.matrixV().transpose();
80template <
typename Derived>
83 E.diagonal().array() -= 1;
84 const_cast<Eigen::MatrixBase<Derived>&
>(R) -= 0.5 * R * E;
#define G2O_TYPES_SLAM3D_API
Isometry3 fromVectorQT(const Vector7 &v)
SE3Quat toSE3Quat(const Isometry3 &t)
Vector3 toEuler(const Matrix3 &R)
void nearestOrthogonalMatrix(const Eigen::MatrixBase< Derived > &R)
Isometry3 fromVectorMQT(const Vector6 &v)
Vector6 toVectorMQT(const Isometry3 &t)
Vector3 toCompactQuaternion(const Matrix3 &R)
Quaternion normalized(const Quaternion &q)
Matrix3 fromCompactQuaternion(const Vector3 &v)
Quaternion & normalize(Quaternion &q)
void approximateNearestOrthogonalMatrix(const Eigen::MatrixBase< Derived > &R)
Matrix3 fromEuler(const Vector3 &v)
Vector6 toVectorET(const Isometry3 &t)
Vector7 toVectorQT(const Isometry3 &t)
Isometry3 fromVectorET(const Vector6 &v)
Isometry3 fromSE3Quat(const SE3Quat &t)
Isometry3::ConstLinearPart extractRotation(const Isometry3 &A)
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3
Eigen::Quaternion< double > Quaternion