Cholesky decompositions. More...
| Functions | |
| template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Mat > | |
| Mat & | computeMinv (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Mat > &Minv) | 
| Computes the inverse of the joint space inertia matrix M from its Cholesky factorization.  More... | |
| template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
| const DataTpl< Scalar, Options, JointCollectionTpl >::RowMatrixXs & | computeMinv (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) | 
| Computes the inverse of the joint space inertia matrix M from its Cholesky factorization. The results is then directly stored in data.Minv.  More... | |
| template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl> | |
| const DataTpl< Scalar, Options, JointCollectionTpl >::MatrixXs & | decompose (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data) | 
| Compute the Cholesky decomposition of the joint space inertia matrix M contained in data.  More... | |
| template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Mat , typename MatRes > | |
| MatRes & | Mv (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Mat > &min, const Eigen::MatrixBase< MatRes > &mout) | 
| Performs the multiplication  by using the sparsity pattern of the M matrix.  More... | |
| template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Mat > | |
| PINOCCHIO_EIGEN_PLAIN_TYPE (Mat) Mv(const ModelTpl< Scalar | |
| Performs the multiplication  by using the sparsity pattern of the M matrix.  More... | |
| template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Mat > | |
| Mat & | solve (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Mat > &y) | 
| Return the solution  of  using the Cholesky decomposition stored in data given the entry  . Act like solveInPlace of Eigen::LLT.  More... | |
| template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Mat > | |
| Mat & | UDUtv (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Mat > &m) | 
| Performs the multiplication  by using the Cholesky decomposition of M stored in data.  More... | |
| template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Mat > | |
| Mat & | Uiv (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Mat > &v) | 
| Perform the pivot inversion  using the Cholesky decomposition stored in data and acting in place.  More... | |
| template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Mat > | |
| Mat & | Utiv (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Mat > &v) | 
| Perform the pivot inversion  using the Cholesky decomposition stored in data and acting in place.  More... | |
| template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Mat > | |
| Mat & | Utv (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Mat > &v) | 
| Perform the sparse multiplication  using the Cholesky decomposition stored in data and acting in place.  More... | |
| template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Mat > | |
| Mat & | Uv (const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< Mat > &v) | 
| Perform the sparse multiplication  using the Cholesky decomposition stored in data and acting in place.  More... | |
| Variables | |
| JointCollectionTpl const DataTpl< Scalar, Options, JointCollectionTpl > & | data | 
| JointCollectionTpl const DataTpl< Scalar, Options, JointCollectionTpl > const Eigen::MatrixBase< Mat > & | min | 
| JointCollectionTpl & | model | 
| Options | |
Cholesky decompositions.
| Mat& pinocchio::cholesky::computeMinv | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, | 
| const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
| const Eigen::MatrixBase< Mat > & | Minv | ||
| ) | 
Computes the inverse of the joint space inertia matrix M from its Cholesky factorization.
| JointCollection | Collection of Joint types. | 
| [in] | model | The model structure of the rigid body system. | 
| [in] | data | The data structure of the rigid body system. | 
| [out] | Minv | The output matrix where the result is stored. | 
| const DataTpl<Scalar,Options,JointCollectionTpl>::RowMatrixXs& pinocchio::cholesky::computeMinv | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, | 
| DataTpl< Scalar, Options, JointCollectionTpl > & | data | ||
| ) | 
Computes the inverse of the joint space inertia matrix M from its Cholesky factorization. The results is then directly stored in data.Minv.
| JointCollection | Collection of Joint types. | 
| [in] | model | The model structure of the rigid body system. | 
| [in] | data | The data structure of the rigid body system. | 
Definition at line 223 of file cholesky.hpp.
| 
 | inline | 
Compute the Cholesky decomposition of the joint space inertia matrix M contained in data.
 with
 with  an upper triangular matrix with ones on its main diagonal and
 an upper triangular matrix with ones on its main diagonal and  a diagonal matrix.
 a diagonal matrix. The result stored in data.U and data.D matrices. One can retrieve the matrice M by performing the computation data.U * data.D * data.U.transpose() See https://en.wikipedia.org/wiki/Cholesky_decomposition for futher details.
| JointCollection | Collection of Joint types. | 
| [in] | model | The model structure of the rigid body system. | 
| [in] | data | The data structure of the rigid body system. | 
 .
. | MatRes& pinocchio::cholesky::Mv | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, | 
| const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
| const Eigen::MatrixBase< Mat > & | min, | ||
| const Eigen::MatrixBase< MatRes > & | mout | ||
| ) | 
Performs the multiplication  by using the sparsity pattern of the M matrix.
 by using the sparsity pattern of the M matrix. 
| JointCollection | Collection of Joint types. | 
| [in] | model | The model structure of the rigid body system. | 
| [in] | data | The data structure of the rigid body system. | 
| [in] | min | The input matrix to multiply with data.M. | 
| [out] | mout | The output matrix where the result of  is stored. | 
 .
. | pinocchio::cholesky::PINOCCHIO_EIGEN_PLAIN_TYPE | ( | Mat | ) | const | 
Performs the multiplication  by using the sparsity pattern of the M matrix.
 by using the sparsity pattern of the M matrix. 
| JointCollection | Collection of Joint types. | 
| [in] | model | The model structure of the rigid body system. | 
| [in] | data | The data structure of the rigid body system. | 
| [in] | min | The input matrix to multiply with data.M. | 
 .
. | Mat & pinocchio::cholesky::solve | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, | 
| const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
| const Eigen::MatrixBase< Mat > & | y | ||
| ) | 
Return the solution  of
 of  using the Cholesky decomposition stored in data given the entry
 using the Cholesky decomposition stored in data given the entry  . Act like solveInPlace of Eigen::LLT.
. Act like solveInPlace of Eigen::LLT. 
Perform the sparse inversion  using the Cholesky decomposition stored in data and acting in place.
 using the Cholesky decomposition stored in data and acting in place.
 from the current joint torque
 from the current joint torque  
 
| JointCollection | Collection of Joint types. | 
| [in] | model | The model structure of the rigid body system. | 
| [in] | data | The data structure of the rigid body system. | 
| [in,out] | y | The input matrix to inverse which also contains the result  of the inversion. | 
| JointCollection | Collection of Joint types. | 
| [in] | model | The model structure of the rigid body system. | 
| [in] | data | The data structure of the rigid body system. | 
| [in,out] | v | The input matrix to multiply with data.M^{-1} and also storing the result. | 
 stored in v.
 stored in v. | Mat& pinocchio::cholesky::UDUtv | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, | 
| const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
| const Eigen::MatrixBase< Mat > & | m | ||
| ) | 
Performs the multiplication  by using the Cholesky decomposition of M stored in data.
 by using the Cholesky decomposition of M stored in data. 
| JointCollection | Collection of Joint types. | 
| [in] | model | The model structure of the rigid body system. | 
| [in] | data | The data structure of the rigid body system. | 
| [in,out] | m | The input matrix where the result of  is stored. | 
 .
. | Mat& pinocchio::cholesky::Uiv | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, | 
| const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
| const Eigen::MatrixBase< Mat > & | v | ||
| ) | 
Perform the pivot inversion  using the Cholesky decomposition stored in data and acting in place.
 using the Cholesky decomposition stored in data and acting in place. 
| JointCollection | Collection of Joint types. | 
| [in] | model | The model structure of the rigid body system. | 
| [in] | data | The data structure of the rigid body system. | 
| [in,out] | v | The input matrix to multiply with data.U^{-1} and also storing the result. | 
 stored in v.
 stored in v.| Mat& pinocchio::cholesky::Utiv | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, | 
| const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
| const Eigen::MatrixBase< Mat > & | v | ||
| ) | 
Perform the pivot inversion  using the Cholesky decomposition stored in data and acting in place.
 using the Cholesky decomposition stored in data and acting in place. 
| JointCollection | Collection of Joint types. | 
| [in] | model | The model structure of the rigid body system. | 
| [in] | data | The data structure of the rigid body system. | 
| [in,out] | v | The input matrix to multiply with data.U^{-} and also storing the result. | 
 stored in v.
 stored in v.| Mat& pinocchio::cholesky::Utv | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, | 
| const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
| const Eigen::MatrixBase< Mat > & | v | ||
| ) | 
Perform the sparse multiplication  using the Cholesky decomposition stored in data and acting in place.
 using the Cholesky decomposition stored in data and acting in place. 
| JointCollection | Collection of Joint types. | 
| [in] | model | The model structure of the rigid body system. | 
| [in] | data | The data structure of the rigid body system. | 
| [in,out] | v | The input matrix to multiply with data.U.tranpose() and also storing the result. | 
 stored in v.
 stored in v. | Mat& pinocchio::cholesky::Uv | ( | const ModelTpl< Scalar, Options, JointCollectionTpl > & | model, | 
| const DataTpl< Scalar, Options, JointCollectionTpl > & | data, | ||
| const Eigen::MatrixBase< Mat > & | v | ||
| ) | 
Perform the sparse multiplication  using the Cholesky decomposition stored in data and acting in place.
 using the Cholesky decomposition stored in data and acting in place. 
| JointCollection | Collection of Joint types. | 
| [in] | model | The model structure of the rigid body system. | 
| [in] | data | The data structure of the rigid body system. | 
| [in,out] | v | The input matrix to multiply with data.U and also storing the result. | 
 stored in v.
 stored in v. Definition at line 71 of file cholesky.hpp.
| JointCollectionTpl const DataTpl<Scalar,Options,JointCollectionTpl> const Eigen::MatrixBase<Mat>& pinocchio::cholesky::min | 
Definition at line 71 of file cholesky.hpp.
| JointCollectionTpl& pinocchio::cholesky::model | 
Definition at line 71 of file cholesky.hpp.
| pinocchio::cholesky::Options | 
Definition at line 71 of file cholesky.hpp.