constrained-dynamics.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2019-2021 INRIA
3 //
4 
5 #ifndef __pinocchio_algorithm_constrained_dynamics_hpp__
6 #define __pinocchio_algorithm_constrained_dynamics_hpp__
7 
9 
11 
12 namespace pinocchio
13 {
14 
29  template<
30  typename Scalar,
31  int Options,
32  template<typename, int>
33  class JointCollectionTpl,
34  class Allocator>
35  PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility")
36  inline void initConstraintDynamics(
37  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
38  DataTpl<Scalar, Options, JointCollectionTpl> & data,
39  const std::vector<RigidConstraintModelTpl<Scalar, Options>, Allocator> & contact_models);
40 
78  template<
79  typename Scalar,
80  int Options,
81  template<typename, int>
82  class JointCollectionTpl,
83  typename ConfigVectorType,
84  typename TangentVectorType1,
85  typename TangentVectorType2,
86  class ConstraintModelAllocator,
87  class ConstraintDataAllocator>
88  PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility")
89  inline const
90  typename DataTpl<Scalar, Options, JointCollectionTpl>::TangentVectorType & constraintDynamics(
91  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
92  DataTpl<Scalar, Options, JointCollectionTpl> & data,
93  const Eigen::MatrixBase<ConfigVectorType> & q,
94  const Eigen::MatrixBase<TangentVectorType1> & v,
95  const Eigen::MatrixBase<TangentVectorType2> & tau,
96  const std::vector<RigidConstraintModelTpl<Scalar, Options>, ConstraintModelAllocator> &
98  std::vector<RigidConstraintDataTpl<Scalar, Options>, ConstraintDataAllocator> & contact_datas,
99  ProximalSettingsTpl<Scalar> & settings);
100 
135  template<
136  typename Scalar,
137  int Options,
138  template<typename, int>
139  class JointCollectionTpl,
140  typename ConfigVectorType,
141  typename TangentVectorType1,
142  typename TangentVectorType2,
143  class ConstraintModelAllocator,
144  class ConstraintDataAllocator>
145  PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility")
146  inline const
147  typename DataTpl<Scalar, Options, JointCollectionTpl>::TangentVectorType & constraintDynamics(
148  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
149  DataTpl<Scalar, Options, JointCollectionTpl> & data,
150  const Eigen::MatrixBase<ConfigVectorType> & q,
151  const Eigen::MatrixBase<TangentVectorType1> & v,
152  const Eigen::MatrixBase<TangentVectorType2> & tau,
153  const std::vector<RigidConstraintModelTpl<Scalar, Options>, ConstraintModelAllocator> &
155  std::vector<RigidConstraintDataTpl<Scalar, Options>, ConstraintDataAllocator> & contact_datas)
156  {
159  }
160 
161  template<
162  typename Scalar,
163  int Options,
164  template<typename, int>
165  class JointCollectionTpl,
166  typename ConfigVectorType,
167  typename TangentVectorType1,
168  typename TangentVectorType2,
169  class ModelAllocator,
170  class DataAllocator>
171  PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility")
172  inline const
173  typename DataTpl<Scalar, Options, JointCollectionTpl>::TangentVectorType & contactABA(
174  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
175  DataTpl<Scalar, Options, JointCollectionTpl> & data,
176  const Eigen::MatrixBase<ConfigVectorType> & q,
177  const Eigen::MatrixBase<TangentVectorType1> & v,
178  const Eigen::MatrixBase<TangentVectorType2> & tau,
179  const std::vector<RigidConstraintModelTpl<Scalar, Options>, ModelAllocator> & contact_models,
180  std::vector<RigidConstraintDataTpl<Scalar, Options>, DataAllocator> & contact_data)
181  {
183  return contactABA(
184  model, data, q.derived(), v.derived(), tau.derived(), contact_models, contact_data, settings);
185  }
186 
187 } // namespace pinocchio
188 
189 #include "pinocchio/algorithm/constrained-dynamics.hxx"
190 
191 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
192  #include "pinocchio/algorithm/constrained-dynamics.txx"
193 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
194 
195 #endif // ifndef __pinocchio_algorithm_constrained_dynamics_hpp__
Eigen
pinocchio::DataTpl
Definition: context/generic.hpp:25
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
simulation-contact-dynamics.contact_datas
list contact_datas
Definition: simulation-contact-dynamics.py:65
forward-dynamics-derivatives.tau
tau
Definition: forward-dynamics-derivatives.py:23
proximal.hpp
pinocchio::ProximalSettingsTpl
Structure containing all the settings paramters for the proximal algorithms.
Definition: algorithm/fwd.hpp:13
pinocchio::RigidConstraintModelTpl
Definition: algorithm/constraints/fwd.hpp:14
pinocchio::RigidConstraintDataTpl
Definition: algorithm/constraints/fwd.hpp:16
pinocchio::initConstraintDynamics
void initConstraintDynamics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const std::vector< RigidConstraintModelTpl< Scalar, Options >, Allocator > &contact_models)
Init the forward dynamics data according to the contact information contained in contact_models.
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1117
pinocchio::v
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > const Eigen::MatrixBase< TangentVectorType > & v
Definition: joint-configuration.hpp:1118
pinocchio::contactABA
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & contactABA(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &tau, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, DataAllocator > &contact_data)
Definition: constrained-dynamics.hpp:173
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::ModelTpl
Definition: context/generic.hpp:20
pinocchio::constraintDynamics
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & constraintDynamics(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< ConfigVectorType > &q, const Eigen::MatrixBase< TangentVectorType1 > &v, const Eigen::MatrixBase< TangentVectorType2 > &tau, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_datas, ProximalSettingsTpl< Scalar > &settings)
Computes the forward dynamics with contact constraints according to a given list of Contact informati...
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1116
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Sat Jun 22 2024 02:41:45