rotation.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2019-2020 CNRS INRIA
3 //
4 
5 #ifndef __pinocchio_math_rotation_hpp__
6 #define __pinocchio_math_rotation_hpp__
7 
8 #include "pinocchio/fwd.hpp"
11 
12 #include <Eigen/Core>
13 #include <Eigen/Geometry>
14 #include <Eigen/SVD>
15 
16 namespace pinocchio
17 {
18 
25  template<typename Vector3, typename Scalar, typename Matrix3>
27  const Eigen::MatrixBase<Vector3> & axis,
28  const Scalar & cos_value,
29  const Scalar & sin_value,
30  const Eigen::MatrixBase<Matrix3> & res)
31  {
32  EIGEN_STATIC_ASSERT_VECTOR_SPECIFIC_SIZE(Vector3, 3);
33  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix3, 3, 3);
34 
35  assert(isUnitary(axis) && "The axis is not unitary.");
36 
37  Matrix3 & res_ = PINOCCHIO_EIGEN_CONST_CAST(Matrix3, res);
38  Vector3 sin_axis = sin_value * axis;
39  Vector3 cos1_axis = (Scalar(1) - cos_value) * axis;
40 
41  Scalar tmp;
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();
45 
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();
49 
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();
53 
54  res_.diagonal() = (cos1_axis.cwiseProduct(axis)).array() + cos_value;
55  }
56 
63  template<typename Vector3, typename Scalar, typename Matrix3>
65  const Eigen::MatrixBase<Vector3> & axis,
66  const Scalar & angle,
67  const Eigen::MatrixBase<Matrix3> & res)
68  {
69  Scalar sa, ca;
70  SINCOS(angle, &sa, &ca);
72  }
73 
79  template<typename Matrix3>
80  void normalizeRotation(const Eigen::MatrixBase<Matrix3> & rot)
81  {
82  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix3, 3, 3);
83  Matrix3 & rot_ = PINOCCHIO_EIGEN_CONST_CAST(Matrix3, rot);
84 
85  typedef typename Matrix3::Scalar Scalar;
86  enum
87  {
89  };
90  typedef Eigen::Quaternion<Scalar, Options> Quaternion;
91  Quaternion quat(rot);
92  normalize(quat.coeffs());
93  rot_ = quat.toRotationMatrix();
94  }
95 
103  template<typename Matrix3>
104  typename PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3)
105  orthogonalProjection(const Eigen::MatrixBase<Matrix3> & mat)
106  {
107  EIGEN_STATIC_ASSERT_MATRIX_SPECIFIC_SIZE(Matrix3, 3, 3);
108  typedef typename PINOCCHIO_EIGEN_PLAIN_TYPE(Matrix3) ReturnType;
109 
110  typedef Eigen::JacobiSVD<Matrix3> SVD;
111  const SVD svd(mat, Eigen::ComputeFullU | Eigen::ComputeFullV);
112 
113  ReturnType res;
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));
117  return res;
118  }
119 } // namespace pinocchio
120 
121 #endif // #ifndef __pinocchio_math_rotation_hpp__
sincos.hpp
pinocchio::isUnitary
bool isUnitary(const Eigen::MatrixBase< MatrixLike > &mat, const typename MatrixLike::RealScalar &prec=Eigen::NumTraits< typename MatrixLike::Scalar >::dummy_precision())
Check whether the input matrix is Unitary within the given precision.
Definition: math/matrix.hpp:155
pinocchio::normalizeRotation
void normalizeRotation(const Eigen::MatrixBase< Matrix3 > &rot)
Orthogonormalization procedure for a rotation matrix (closed enough to SO(3)).
Definition: rotation.hpp:80
quat
quat
pinocchio::Options
Options
Definition: joint-configuration.hpp:1116
PINOCCHIO_EIGEN_CONST_CAST
#define PINOCCHIO_EIGEN_CONST_CAST(TYPE, OBJ)
Macro for an automatic const_cast.
Definition: eigen-macros.hpp:51
fwd.hpp
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
pinocchio::res
ReturnType res
Definition: spatial/classic-acceleration.hpp:57
pinocchio::SINCOS
void SINCOS(const S1 &a, S2 *sa, S3 *ca)
Computes sin/cos values of a given input scalar.
Definition: sincos.hpp:27
pinocchio::python::context::Quaternion
Eigen::Quaternion< Scalar, Options > Quaternion
Definition: bindings/python/context/generic.hpp:49
matrix.hpp
mat
mat
pinocchio::context::Vector3
Eigen::Matrix< Scalar, 3, 1, Options > Vector3
Definition: context/generic.hpp:53
axis
axis
pinocchio::toRotationMatrix
void toRotationMatrix(const Eigen::MatrixBase< Vector3 > &axis, const Scalar &cos_value, const Scalar &sin_value, const Eigen::MatrixBase< Matrix3 > &res)
Computes a rotation matrix from a vector and values of sin and cos orientations values.
Definition: rotation.hpp:26
pinocchio::PINOCCHIO_EIGEN_PLAIN_TYPE
PINOCCHIO_EIGEN_PLAIN_TYPE(ConfigVectorType) integrate(const ModelTpl< Scalar
Integrate a configuration vector for the specified model for a tangent vector during one unit time.
pinocchio::normalize
void normalize(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const Eigen::MatrixBase< ConfigVectorType > &qout)
Normalize a configuration vector.
Definition: joint-configuration.hpp:914
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Sat Jun 22 2024 02:41:49