delassus.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2020-2024 INRIA
3 // Copyright (c) 2023 KU Leuven
4 //
5 
6 #ifndef __pinocchio_algorithm_contact_delassus_hpp__
7 #define __pinocchio_algorithm_contact_delassus_hpp__
8 
10 
11 namespace pinocchio
12 {
13 
14  template<
15  typename Scalar,
16  int Options,
17  template<typename, int>
18  class JointCollectionTpl,
19  class Allocator>
20  PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility")
21  inline void initPvDelassus(
22  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
23  DataTpl<Scalar, Options, JointCollectionTpl> & data,
24  const std::vector<RigidConstraintModelTpl<Scalar, Options>, Allocator> & contact_models);
25 
44  template<
45  typename Scalar,
46  int Options,
47  template<typename, int>
48  class JointCollectionTpl,
49  typename ConfigVectorType,
50  class ModelAllocator,
51  class DataAllocator,
52  typename MatrixType>
53  PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility")
55  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
56  DataTpl<Scalar, Options, JointCollectionTpl> & data,
57  const Eigen::MatrixBase<ConfigVectorType> & q,
58  const std::vector<RigidConstraintModelTpl<Scalar, Options>, ModelAllocator> & contact_models,
59  std::vector<RigidConstraintDataTpl<Scalar, Options>, DataAllocator> & contact_data,
60  const Eigen::MatrixBase<MatrixType> & delassus,
61  const Scalar mu = 0);
62 
86  template<
87  typename Scalar,
88  int Options,
89  template<typename, int>
90  class JointCollectionTpl,
91  typename ConfigVectorType,
92  class ModelAllocator,
93  class DataAllocator,
94  typename MatrixType>
95  PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility")
97  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
98  DataTpl<Scalar, Options, JointCollectionTpl> & data,
99  const Eigen::MatrixBase<ConfigVectorType> & q,
100  const std::vector<RigidConstraintModelTpl<Scalar, Options>, ModelAllocator> & contact_models,
101  std::vector<RigidConstraintDataTpl<Scalar, Options>, DataAllocator> & contact_data,
102  const Eigen::MatrixBase<MatrixType> & damped_delassus_inverse,
103  const Scalar mu,
104  const bool scaled = false,
105  const bool Pv = true);
106 
107 } // namespace pinocchio
108 
109 #include "pinocchio/algorithm/delassus.hxx"
110 
111 #endif // ifndef __pinocchio_algorithm_contact_delassus_hpp__
pinocchio::computeDampedDelassusMatrixInverse
void computeDampedDelassusMatrixInverse(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, DataAllocator > &contact_data, const Eigen::MatrixBase< MatrixType > &damped_delassus_inverse, const Scalar mu, const bool scaled=false, const bool Pv=true)
Computes the inverse of the Delassus matrix associated to a set of given constraints.
Eigen
pinocchio::computeDelassusMatrix
void computeDelassusMatrix(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, DataAllocator > &contact_data, const Eigen::MatrixBase< MatrixType > &delassus, const Scalar mu=0)
Computes the Delassus matrix associated to a set of given constraints.
pinocchio::Options
Options
Definition: joint-configuration.hpp:1116
contact-cholesky.contact_data
list contact_data
Definition: contact-cholesky.py:36
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::PINOCCHIO_UNSUPPORTED_MESSAGE
struct PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility") ContactCholeskyDecompositionTpl
Contact Cholesky decomposition structure. This structure allows to compute in a efficient and parsimo...
Definition: algorithm/contact-cholesky.hpp:55
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
pinocchio::initPvDelassus
void initPvDelassus(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const std::vector< RigidConstraintModelTpl< Scalar, Options >, Allocator > &contact_models)
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1117
mu
double mu
Definition: delassus.cpp:58
std
Definition: autodiff/casadi/utils/static-if.hpp:64
contact-cholesky.contact_models
list contact_models
Definition: contact-cholesky.py:25
contact-info.hpp
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Tue Jun 25 2024 02:42:37