5 #ifndef __pinocchio_cholesky_hpp__ 6 #define __pinocchio_cholesky_hpp__ 8 #include "pinocchio/multibody/model.hpp" 9 #include "pinocchio/multibody/data.hpp" 34 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl>
36 decompose(
const ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
37 DataTpl<Scalar,Options,JointCollectionTpl> &
data);
53 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename Mat>
54 Mat &
solve(
const ModelTpl<Scalar,Options,JointCollectionTpl> &
model,
55 const DataTpl<Scalar,Options,JointCollectionTpl> &
data,
56 const Eigen::MatrixBase<Mat> & y);
69 template<
typename Scalar,
int Options,
template<
typename,
int>
class JointCollectionTpl,
typename Mat>
72 const
DataTpl<Scalar,Options,JointCollectionTpl> &
data,
87 template<typename Scalar,
int Options, template<typename,
int> class JointCollectionTpl, typename Mat, typename MatRes>
88 MatRes &
Mv(const
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
89 const
DataTpl<Scalar,Options,JointCollectionTpl> & data,
90 const
Eigen::MatrixBase<Mat> & min,
91 const
Eigen::MatrixBase<MatRes> & mout);
105 template<typename Scalar,
int Options, template<typename,
int> class JointCollectionTpl, typename Mat>
106 Mat &
UDUtv(const
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
107 const
DataTpl<Scalar,Options,JointCollectionTpl> & data,
108 const
Eigen::MatrixBase<Mat> & m);
121 template<typename Scalar,
int Options, template<typename,
int> class JointCollectionTpl, typename Mat>
122 Mat &
Uv(const
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
123 const
DataTpl<Scalar,Options,JointCollectionTpl> & data,
124 const
Eigen::MatrixBase<Mat> &
v);
137 template<typename Scalar,
int Options, template<typename,
int> class JointCollectionTpl, typename Mat>
138 Mat &
Utv(const
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
139 const
DataTpl<Scalar,Options,JointCollectionTpl> & data,
140 const
Eigen::MatrixBase<Mat> & v);
155 template<typename Scalar,
int Options, template<typename,
int> class JointCollectionTpl, typename Mat>
156 Mat &
Uiv(const
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
157 const
DataTpl<Scalar,Options,JointCollectionTpl> & data ,
158 const
Eigen::MatrixBase<Mat> & v);
173 template<typename Scalar,
int Options, template<typename,
int> class JointCollectionTpl, typename Mat>
174 Mat &
Utiv(const
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
175 const
DataTpl<Scalar,Options,JointCollectionTpl> & data ,
176 const
Eigen::MatrixBase<Mat> & v);
189 template<typename Scalar,
int Options, template<typename,
int> class JointCollectionTpl, typename Mat>
190 Mat &
solve(const
ModelTpl<Scalar,Options,JointCollectionTpl> & model,
191 const
DataTpl<Scalar,Options,JointCollectionTpl> & data ,
192 const
Eigen::MatrixBase<Mat> & v);
205 template<typename Scalar,
int Options, template<typename,
int> class JointCollectionTpl, typename Mat>
207 const
DataTpl<Scalar,Options,JointCollectionTpl> & data,
208 const
Eigen::MatrixBase<Mat> & Minv);
221 template<typename Scalar,
int Options, template<typename,
int> class JointCollectionTpl>
222 const typename
DataTpl<Scalar,Options,JointCollectionTpl>::RowMatrixXs &
224 DataTpl<Scalar,Options,JointCollectionTpl> & data)
235 #include "pinocchio/algorithm/cholesky.hxx" 237 #endif // ifndef __pinocchio_cholesky_hpp__ JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
PINOCCHIO_EIGEN_PLAIN_TYPE(Mat) Mv(const ModelTpl< Scalar
Performs the multiplication by using the sparsity pattern of the M matrix.
JointCollectionTpl const DataTpl< Scalar, Options, JointCollectionTpl > const Eigen::MatrixBase< Mat > & min
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.
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...
JointCollectionTpl & model
JointCollectionTpl const DataTpl< Scalar, Options, JointCollectionTpl > & data
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...
Eigen::Matrix< Scalar, Eigen::Dynamic, Eigen::Dynamic, Options > MatrixXs
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 plac...
Main pinocchio namespace.
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.
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...
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 ...
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.
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 plac...