27 #ifndef G2O_ISOMETRY3D_MAPPINGS_H_ 28 #define G2O_ISOMETRY3D_MAPPINGS_H_ 33 #include <Eigen/Geometry> 37 typedef Eigen::Matrix<double, 6, 1, Eigen::ColMajor>
Vector6d;
38 typedef Eigen::Matrix<double, 7, 1, Eigen::ColMajor>
Vector7d;
60 return A.matrix().topLeftCorner<3,3>();
69 template <
typename Derived>
72 Eigen::JacobiSVD<Matrix3D> svd(R, Eigen::ComputeFullU | Eigen::ComputeFullV);
73 double det = (svd.matrixU() * svd.matrixV().adjoint()).determinant();
75 scaledU.col(0) /= det;
76 const_cast<Eigen::MatrixBase<Derived>&
>(R) = scaledU * svd.matrixV().transpose();
84 template <
typename Derived>
88 E.diagonal().array() -= 1;
89 const_cast<Eigen::MatrixBase<Derived>&
>(R) -= 0.5 * R * E;
Vector3D toEuler(const Matrix3D &R)
void nearestOrthogonalMatrix(const Eigen::MatrixBase< Derived > &R)
Matrix3D fromCompactQuaternion(const Vector3D &v)
Eigen::Matrix< double, 3, 1, Eigen::ColMajor > Vector3D
Isometry3D fromVectorQT(const Vector7d &v)
Eigen::Matrix< double, 7, 1 > Vector7d
Vector3D toCompactQuaternion(const Matrix3D &R)
SE3Quat toSE3Quat(const Isometry3D &t)
Vector6d toVectorET(const Isometry3D &t)
#define G2O_TYPES_SLAM3D_API
Eigen::Transform< double, 3, Eigen::Isometry, Eigen::ColMajor > Isometry3D
Eigen::Quaterniond & normalize(Eigen::Quaterniond &q)
Vector6d toVectorMQT(const Isometry3D &t)
Isometry3D::ConstLinearPart extractRotation(const Isometry3D &A)
Eigen::Matrix< double, 3, 3, Eigen::ColMajor > Matrix3D
Eigen::Quaterniond normalized(const Eigen::Quaterniond &q)
void approximateNearestOrthogonalMatrix(const Eigen::MatrixBase< Derived > &R)
Vector7d toVectorQT(const Isometry3D &t)
Isometry3D fromVectorMQT(const Vector6d &v)
Isometry3D fromVectorET(const Vector6d &v)
Isometry3D fromSE3Quat(const SE3Quat &t)
Matrix< double, 6, 1, Eigen::ColMajor > Vector6d
Matrix3D fromEuler(const Vector3D &v)