contact-jacobian.hpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2021 INRIA
3 //
4 
5 #ifndef __pinocchio_algorithm_contact_jacobian_hpp__
6 #define __pinocchio_algorithm_contact_jacobian_hpp__
7 
9 
10 namespace pinocchio
11 {
12 
23  template<
24  typename Scalar,
25  int Options,
26  template<typename, int> class JointCollectionTpl,
27  typename Matrix6Like>
28  PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility")
30  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
31  const DataTpl<Scalar, Options, JointCollectionTpl> & data,
32  const RigidConstraintModelTpl<Scalar, Options> & constraint_model,
33  RigidConstraintDataTpl<Scalar, Options> & constraint_data,
34  const Eigen::MatrixBase<Matrix6Like> & J);
35 
46  template<
47  typename Scalar,
48  int Options,
49  template<typename, int> class JointCollectionTpl,
50  typename DynamicMatrixLike,
51  class ConstraintModelAllocator,
52  class ConstraintDataAllocator>
53  PINOCCHIO_UNSUPPORTED_MESSAGE("The API will change towards more flexibility")
55  const ModelTpl<Scalar, Options, JointCollectionTpl> & model,
56  const DataTpl<Scalar, Options, JointCollectionTpl> & data,
57  const std::vector<RigidConstraintModelTpl<Scalar, Options>, ConstraintDataAllocator> &
59  std::vector<RigidConstraintDataTpl<Scalar, Options>, ConstraintDataAllocator> & constraint_data,
60  const Eigen::MatrixBase<DynamicMatrixLike> & J);
61 
62 } // namespace pinocchio
63 
64 #include "pinocchio/algorithm/contact-jacobian.hxx"
65 
66 #if PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
67  #include "pinocchio/algorithm/contact-jacobian.txx"
68 #endif // PINOCCHIO_ENABLE_TEMPLATE_INSTANTIATION
69 
70 #endif // ifndef __pinocchio_algorithm_contact_jacobian_hpp__
Eigen
simulation-closed-kinematic-chains.constraint_model
constraint_model
Definition: simulation-closed-kinematic-chains.py:98
pinocchio::Options
Options
Definition: joint-configuration.hpp:1082
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
inverse-kinematics-3d.J
J
Definition: inverse-kinematics-3d.py:28
simulation-closed-kinematic-chains.constraint_data
constraint_data
Definition: simulation-closed-kinematic-chains.py:106
pinocchio::getConstraintJacobian
void getConstraintJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const RigidConstraintModelTpl< Scalar, Options > &constraint_model, RigidConstraintDataTpl< Scalar, Options > &constraint_data, const Eigen::MatrixBase< Matrix6Like > &J)
Computes the kinematic Jacobian associatied to a given constraint model.
std
Definition: autodiff/casadi/utils/static-if.hpp:64
pinocchio::getConstraintsJacobian
void getConstraintsJacobian(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, const DataTpl< Scalar, Options, JointCollectionTpl > &data, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintDataAllocator > &constraint_model, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &constraint_data, const Eigen::MatrixBase< DynamicMatrixLike > &J)
Computes the kinematic Jacobian associatied to a given set of constraint models.
contact-info.hpp
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1082
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:43