7 #ifndef PINOCCHIO_SKIP_ALGORITHM_CONTACT_CHOLESKY
19 inverseAlgo<context::Scalar, context::Options, context::VectorXs>(
20 const ContactCholeskyDecompositionTpl<context::Scalar, context::Options> &,
21 const Eigen::DenseIndex,
22 const Eigen::MatrixBase<context::VectorXs> &);
24 template struct PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
25 ContactCholeskyDecompositionTpl<context::Scalar, context::Options>;
27 template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
void
28 ContactCholeskyDecompositionTpl<context::Scalar, context::Options>::allocate<
31 JointCollectionDefaultTpl,
32 typename context::RigidConstraintModelVector::allocator_type>(
33 const context::Model &,
const context::RigidConstraintModelVector &);
35 template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
void
36 ContactCholeskyDecompositionTpl<context::Scalar, context::Options>::
37 getInverseOperationalSpaceInertiaMatrix<context::MatrixXs>(
38 const Eigen::MatrixBase<context::MatrixXs> &)
const;
40 template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
void
41 ContactCholeskyDecompositionTpl<context::Scalar, context::Options>::
42 getOperationalSpaceInertiaMatrix<context::MatrixXs>(
43 const Eigen::MatrixBase<context::MatrixXs> &)
const;
45 template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
void
46 ContactCholeskyDecompositionTpl<context::Scalar, context::Options>::getInverseMassMatrix<
49 template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
void
50 ContactCholeskyDecompositionTpl<context::Scalar, context::Options>::compute<
53 JointCollectionDefaultTpl,
54 typename context::RigidConstraintModelVector::allocator_type,
55 typename context::RigidConstraintDataVector::allocator_type>(
58 const context::RigidConstraintModelVector &,
59 context::RigidConstraintDataVector &,
62 template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
void
63 ContactCholeskyDecompositionTpl<context::Scalar, context::Options>::solveInPlace<
66 template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
67 ContactCholeskyDecompositionTpl<context::Scalar, context::Options>::Matrix
68 ContactCholeskyDecompositionTpl<context::Scalar, context::Options>::solve<context::MatrixXs>(
69 const Eigen::MatrixBase<
70 ContactCholeskyDecompositionTpl<context::Scalar, context::Options>::Matrix> &)
const;
72 template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
73 ContactCholeskyDecompositionTpl<context::Scalar, context::Options>
74 ContactCholeskyDecompositionTpl<context::Scalar, context::Options>::
75 getMassMatrixChoeslkyDecomposition<
80 template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
void
81 ContactCholeskyDecompositionTpl<context::Scalar, context::Options>::Uv<context::MatrixXs>(
82 const Eigen::MatrixBase<context::MatrixXs> &)
const;
84 template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
void
85 ContactCholeskyDecompositionTpl<context::Scalar, context::Options>::Utv<context::MatrixXs>(
86 const Eigen::MatrixBase<context::MatrixXs> &)
const;
88 template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
void
89 ContactCholeskyDecompositionTpl<context::Scalar, context::Options>::Uiv<context::MatrixXs>(
90 const Eigen::MatrixBase<context::MatrixXs> &)
const;
92 template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
void
93 ContactCholeskyDecompositionTpl<context::Scalar, context::Options>::Utiv<context::MatrixXs>(
94 const Eigen::MatrixBase<context::MatrixXs> &)
const;
96 template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
void
97 ContactCholeskyDecompositionTpl<context::Scalar, context::Options>::matrix<context::MatrixXs>(
98 const Eigen::MatrixBase<context::MatrixXs> &)
const;
100 template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
void
101 ContactCholeskyDecompositionTpl<context::Scalar, context::Options>::inverse<context::MatrixXs>(
102 const Eigen::MatrixBase<context::MatrixXs> &)
const;
104 template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
bool
105 ContactCholeskyDecompositionTpl<context::Scalar, context::Options>::
107 const ContactCholeskyDecompositionTpl<context::Scalar, context::Options> &)
const;
109 template PINOCCHIO_EXPLICIT_INSTANTIATION_DEFINITION_DLLAPI
bool
110 ContactCholeskyDecompositionTpl<context::Scalar, context::Options>::
112 const ContactCholeskyDecompositionTpl<context::Scalar, context::Options> &)
const;
117 #endif // PINOCCHIO_SKIP_ALGORITHM_CONTACT_CHOLESKY