5 #ifndef __pinocchio_math_rotation_hpp__ 
    6 #define __pinocchio_math_rotation_hpp__ 
   13 #include <Eigen/Geometry> 
   25   template<
typename Vector3, 
typename Scalar, 
typename Matrix3>
 
   27     const Eigen::MatrixBase<Vector3> & axis,
 
   30     const Eigen::MatrixBase<Matrix3> & 
res)
 
   32     EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3, 3);
 
   33     EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix3, 3, 3);
 
   38     Vector3 sin_axis = sin_value * 
axis;
 
   39     Vector3 cos1_axis = (
Scalar(1) - cos_value) * 
axis;
 
   42     tmp = cos1_axis.x() * 
axis.y();
 
   43     res_.coeffRef(0, 1) = tmp - sin_axis.z();
 
   44     res_.coeffRef(1, 0) = tmp + sin_axis.z();
 
   46     tmp = cos1_axis.x() * 
axis.z();
 
   47     res_.coeffRef(0, 2) = tmp + sin_axis.y();
 
   48     res_.coeffRef(2, 0) = tmp - sin_axis.y();
 
   50     tmp = cos1_axis.y() * 
axis.z();
 
   51     res_.coeffRef(1, 2) = tmp - sin_axis.x();
 
   52     res_.coeffRef(2, 1) = tmp + sin_axis.x();
 
   54     res_.diagonal() = (cos1_axis.cwiseProduct(
axis)).array() + cos_value;
 
   63   template<
typename Vector3, 
typename Scalar, 
typename Matrix3>
 
   65     const Eigen::MatrixBase<Vector3> & axis,
 
   67     const Eigen::MatrixBase<Matrix3> & 
res)
 
   79   template<
typename Matrix3>
 
   82     EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix3, 3, 3);
 
   90     typedef Eigen::Quaternion<Scalar, Options> 
Quaternion;
 
   93     rot_ = 
quat.toRotationMatrix();
 
  103   template<
typename Matrix3>
 
  105     orthogonalProjection(
const Eigen::MatrixBase<Matrix3> & mat)
 
  107     EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix3, 3, 3);
 
  110     typedef Eigen::JacobiSVD<Matrix3> SVD;
 
  111     const SVD svd(
mat, Eigen::ComputeFullU | Eigen::ComputeFullV);
 
  114     res.template leftCols<2>().noalias() =
 
  115       svd.matrixU() * svd.matrixV().transpose().template leftCols<2>();
 
  116     res.col(2).noalias() = 
res.col(0).cross(
res.col(1));
 
  121 #endif // #ifndef __pinocchio_math_rotation_hpp__