Functions | Variables
pinocchio::cholesky Namespace Reference

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 $ M v $ 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 $ M v $ 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 $x$ of $ M x = y $ using the Cholesky decomposition stored in data given the entry $ y $. 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 $ M v $ 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 $ U^{-1}v $ 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 $ U^{-\top}v $ 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 $ U^{\top}v $ 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 $ Uv $ 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
 

Detailed Description

Cholesky decompositions.

Function Documentation

◆ computeMinv() [1/2]

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Mat >
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.

Template Parameters
JointCollectionCollection of Joint types.
Parameters
[in]modelThe model structure of the rigid body system.
[in]dataThe data structure of the rigid body system.
[out]MinvThe output matrix where the result is stored.
Returns
A reference to the result.

◆ computeMinv() [2/2]

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
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.

Template Parameters
JointCollectionCollection of Joint types.
Parameters
[in]modelThe model structure of the rigid body system.
[in]dataThe data structure of the rigid body system.
Returns
A reference to the result data.Minv.

Definition at line 223 of file cholesky.hpp.

◆ decompose()

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl>
const DataTpl<Scalar,Options,JointCollectionTpl>::MatrixXs& pinocchio::cholesky::decompose ( const ModelTpl< Scalar, Options, JointCollectionTpl > &  model,
DataTpl< Scalar, Options, JointCollectionTpl > &  data 
)
inline

Compute the Cholesky decomposition of the joint space inertia matrix M contained in data.

Note
The Cholesky decomposition corresponds to $ M = U D U^{\top}$ with $U$ an upper triangular matrix with ones on its main diagonal and $D$ 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.

Template Parameters
JointCollectionCollection of Joint types.
Parameters
[in]modelThe model structure of the rigid body system.
[in]dataThe data structure of the rigid body system.
Returns
A reference to the upper triangular matrix $U$.

◆ Mv()

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Mat , typename MatRes >
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 $ M v $ by using the sparsity pattern of the M matrix.

Template Parameters
JointCollectionCollection of Joint types.
Parameters
[in]modelThe model structure of the rigid body system.
[in]dataThe data structure of the rigid body system.
[in]minThe input matrix to multiply with data.M.
[out]moutThe output matrix where the result of $ Mv $ is stored.
Returns
A reference of the result of $ Mv $.

◆ PINOCCHIO_EIGEN_PLAIN_TYPE()

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Mat >
pinocchio::cholesky::PINOCCHIO_EIGEN_PLAIN_TYPE ( Mat  ) const

Performs the multiplication $ M v $ by using the sparsity pattern of the M matrix.

Template Parameters
JointCollectionCollection of Joint types.
Parameters
[in]modelThe model structure of the rigid body system.
[in]dataThe data structure of the rigid body system.
[in]minThe input matrix to multiply with data.M.
Returns
A the result of $ Mv $.

◆ solve()

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Mat >
Mat & pinocchio::cholesky::solve ( const ModelTpl< Scalar, Options, JointCollectionTpl > &  model,
const DataTpl< Scalar, Options, JointCollectionTpl > &  data,
const Eigen::MatrixBase< Mat > &  y 
)

Return the solution $x$ of $ M x = y $ using the Cholesky decomposition stored in data given the entry $ y $. Act like solveInPlace of Eigen::LLT.

Perform the sparse inversion $ M^{-1}v $ using the Cholesky decomposition stored in data and acting in place.

Note
This algorithm is useful to compute the forward dynamics, retriving the joint acceleration $ \ddot{q} $ from the current joint torque $ \tau $ $ M(q) \ddot{q} + b(q, \dot{q}) = \tau \iff \ddot{q} = M(q)^{-1} (\tau - b(q, \dot{q})) $
Template Parameters
JointCollectionCollection of Joint types.
Parameters
[in]modelThe model structure of the rigid body system.
[in]dataThe data structure of the rigid body system.
[in,out]yThe input matrix to inverse which also contains the result $x$ of the inversion.
Template Parameters
JointCollectionCollection of Joint types.
Parameters
[in]modelThe model structure of the rigid body system.
[in]dataThe data structure of the rigid body system.
[in,out]vThe input matrix to multiply with data.M^{-1} and also storing the result.
Returns
A reference to the result of $ M^{-1}v $ stored in v.

◆ UDUtv()

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Mat >
Mat& pinocchio::cholesky::UDUtv ( const ModelTpl< Scalar, Options, JointCollectionTpl > &  model,
const DataTpl< Scalar, Options, JointCollectionTpl > &  data,
const Eigen::MatrixBase< Mat > &  m 
)

Performs the multiplication $ M v $ by using the Cholesky decomposition of M stored in data.

Template Parameters
JointCollectionCollection of Joint types.
Parameters
[in]modelThe model structure of the rigid body system.
[in]dataThe data structure of the rigid body system.
[in,out]mThe input matrix where the result of $ Mv $ is stored.
Returns
A reference of the result of $ Mv $.

◆ Uiv()

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Mat >
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 $ U^{-1}v $ using the Cholesky decomposition stored in data and acting in place.

Template Parameters
JointCollectionCollection of Joint types.
Parameters
[in]modelThe model structure of the rigid body system.
[in]dataThe data structure of the rigid body system.
[in,out]vThe input matrix to multiply with data.U^{-1} and also storing the result.
Returns
A reference to the result of $ U^{-1}v $ stored in v.
Remarks
The result is similar to the code data.U.triangularView<Eigen::Upper> ().solveInPlace(v).

◆ Utiv()

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Mat >
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 $ U^{-\top}v $ using the Cholesky decomposition stored in data and acting in place.

Template Parameters
JointCollectionCollection of Joint types.
Parameters
[in]modelThe model structure of the rigid body system.
[in]dataThe data structure of the rigid body system.
[in,out]vThe input matrix to multiply with data.U^{-\top} and also storing the result.
Returns
A reference to the result of $ U^{-\top}v $ stored in v.
Remarks
The result is similar to the code data.U.triangularView<Eigen::Upper> ().transpose().solveInPlace(v).

◆ Utv()

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Mat >
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 $ U^{\top}v $ using the Cholesky decomposition stored in data and acting in place.

Template Parameters
JointCollectionCollection of Joint types.
Parameters
[in]modelThe model structure of the rigid body system.
[in]dataThe data structure of the rigid body system.
[in,out]vThe input matrix to multiply with data.U.tranpose() and also storing the result.
Returns
A reference to the result of $ U^{\top}v $ stored in v.

◆ Uv()

template<typename Scalar , int Options, template< typename, int > class JointCollectionTpl, typename Mat >
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 $ Uv $ using the Cholesky decomposition stored in data and acting in place.

Template Parameters
JointCollectionCollection of Joint types.
Parameters
[in]modelThe model structure of the rigid body system.
[in]dataThe data structure of the rigid body system.
[in,out]vThe input matrix to multiply with data.U and also storing the result.
Returns
A reference to the result of $ Uv $ stored in v.

Variable Documentation

◆ data

JointCollectionTpl const DataTpl<Scalar,Options,JointCollectionTpl>& pinocchio::cholesky::data

Definition at line 72 of file cholesky.hpp.

◆ min

JointCollectionTpl const DataTpl<Scalar,Options,JointCollectionTpl> const Eigen::MatrixBase<Mat>& pinocchio::cholesky::min

Definition at line 73 of file cholesky.hpp.

◆ model

JointCollectionTpl& pinocchio::cholesky::model

Definition at line 71 of file cholesky.hpp.

◆ Options

pinocchio::cholesky::Options

Definition at line 71 of file cholesky.hpp.



pinocchio
Author(s):
autogenerated on Tue Feb 13 2024 03:44:02