expose-contact-inverse-dynamics.cpp
Go to the documentation of this file.
1 //
2 // Copyright (c) 2024 INRIA
3 //
4 
5 #define BOOST_PYTHON_MAX_ARITY 24
6 
10 
11 namespace pinocchio
12 {
13  namespace python
14  {
15 
16 #ifndef PINOCCHIO_PYTHON_SKIP_ALGORITHM_CONSTRAINED_DYNAMICS
17  typedef context::Scalar Scalar;
19  typedef const Eigen::Ref<const VectorXs> ConstRefVectorXs;
20  enum
21  {
23  };
24 
28  const ConstRefVectorXs & c_ref,
29  const context::RigidConstraintModelVector & contact_models,
30  context::RigidConstraintDataVector & contact_datas,
31  const context::CoulombFrictionConeVector & cones,
32  const ConstRefVectorXs & R,
33  const ConstRefVectorXs & constraint_correction,
34  ProximalSettingsTpl<Scalar> & settings,
35  const boost::optional<ConstRefVectorXs> & lambda_guess = boost::none)
36  {
38  model, data, c_ref, contact_models, contact_datas, cones, R, constraint_correction,
39  settings, lambda_guess);
40  }
41 
48  Scalar dt,
49  const context::RigidConstraintModelVector & contact_models,
50  context::RigidConstraintDataVector & contact_datas,
51  const context::CoulombFrictionConeVector & cones,
52  ConstRefVectorXs & R,
53  ConstRefVectorXs & constraint_correction,
54  ProximalSettingsTpl<Scalar> & settings,
55  const boost::optional<ConstRefVectorXs> & lambda_guess = boost::none)
56  {
58  model, data, q, v, a, dt, contact_models, contact_datas, cones, R, constraint_correction,
59  settings, lambda_guess);
60  }
61 #endif // PINOCCHIO_PYTHON_SKIP_ALGORITHM_CONSTRAINED_DYNAMICS
62 
64  {
65 #ifndef PINOCCHIO_PYTHON_SKIP_ALGORITHM_CONSTRAINED_DYNAMICS
66  bp::def(
67  "computeContactForces", computeContactImpulses_wrapper,
68  (bp::arg("model"), "data", "c_ref", "contact_models", "contact_datas", "cones", "R",
69  "constraint_correction", bp::arg("settings"), bp::arg("lambda_guess") = boost::none),
70  "Compute the inverse dynamics with frictional contacts, store the result in Data and "
71  "return it.\n\n"
72  "Parameters:\n"
73  "\tmodel: model of the kinematic tree\n"
74  "\tdata: data related to the model\n"
75  "\tc_ref: the reference velocity of contact points\n"
76  "\tcontact_models: list of contact models\n"
77  "\tcontact_datas: list of contact datas\n"
78  "\tcones: list of friction cones\n"
79  "\tR: vector representing the diagonal of the compliance matrix\n"
80  "\tconstraint_correction: vector representing the constraint correction\n"
81  "\tsettings: the settings of the proximal algorithm\n"
82  "\tlambda_guess: initial guess for contact forces\n");
83 
84  bp::def(
85  "contactInverseDynamics", contactInverseDynamics_wrapper,
86  (bp::arg("model"), "data", "q", "v", "a", "dt", "contact_models", "contact_datas", "cones",
87  "R", "constraint_correction", bp::arg("settings"), bp::arg("lambda_guess") = boost::none),
88  "Compute the inverse dynamics with frictional contacts, store the result in Data and "
89  "return it.\n\n"
90  "Parameters:\n"
91  "\tmodel: model of the kinematic tree\n"
92  "\tdata: data related to the model\n"
93  "\tq: the joint configuration vector (size model.nq)\n"
94  "\tv: the joint velocity vector (size model.nv)\n"
95  "\ta: the joint acceleration vector (size model.nv)\n"
96  "\tdt: the time step\n"
97  "\tcontact_models: list of contact models\n"
98  "\tcontact_datas: list of contact datas\n"
99  "\tcones: list of friction cones\n"
100  "\tR: vector representing the diagonal of the compliance matrix\n"
101  "\tconstraint_correction: vector representing the constraint correction\n"
102  "\tsettings: the settings of the proximal algorithm\n"
103  "\tlambda_guess: initial guess for contact forces\n");
104 #endif // PINOCCHIO_PYTHON_SKIP_ALGORITHM_CONSTRAINED_DYNAMICS
105  }
106  } // namespace python
107 } // namespace pinocchio
pinocchio::DataTpl
Definition: context/generic.hpp:25
pinocchio::python::contactInverseDynamics_wrapper
static ConstRefVectorXs contactInverseDynamics_wrapper(const ModelTpl< Scalar, Options, JointCollectionDefaultTpl > &model, DataTpl< Scalar, Options, JointCollectionDefaultTpl > &data, ConstRefVectorXs &q, ConstRefVectorXs &v, ConstRefVectorXs &a, Scalar dt, const context::RigidConstraintModelVector &contact_models, context::RigidConstraintDataVector &contact_datas, const context::CoulombFrictionConeVector &cones, ConstRefVectorXs &R, ConstRefVectorXs &constraint_correction, ProximalSettingsTpl< Scalar > &settings, const boost::optional< ConstRefVectorXs > &lambda_guess=boost::none)
Definition: expose-contact-inverse-dynamics.cpp:42
pinocchio::python::exposeContactInverseDynamics
void exposeContactInverseDynamics()
Definition: expose-contact-inverse-dynamics.cpp:63
pinocchio::contactInverseDynamics
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & contactInverseDynamics(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 > &a, Scalar dt, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_datas, const std::vector< CoulombFrictionConeTpl< Scalar >, CoulombFrictionConelAllocator > &cones, const Eigen::MatrixBase< VectorLikeR > &R, const Eigen::MatrixBase< VectorLikeGamma > &constraint_correction, ProximalSettingsTpl< Scalar > &settings, const boost::optional< VectorLikeLam > &lambda_guess=boost::none)
The Contact Inverse Dynamics algorithm. It computes the inverse dynamics in the presence of contacts,...
Definition: contact-inverse-dynamics.hpp:190
setup.data
data
Definition: cmake/cython/setup.in.py:48
pinocchio::python::Scalar
context::Scalar Scalar
Definition: admm-solver.cpp:29
pinocchio::python::computeContactImpulses_wrapper
static ConstRefVectorXs computeContactImpulses_wrapper(const ModelTpl< Scalar, Options, JointCollectionDefaultTpl > &model, DataTpl< Scalar, Options, JointCollectionDefaultTpl > &data, const ConstRefVectorXs &c_ref, const context::RigidConstraintModelVector &contact_models, context::RigidConstraintDataVector &contact_datas, const context::CoulombFrictionConeVector &cones, const ConstRefVectorXs &R, const ConstRefVectorXs &constraint_correction, ProximalSettingsTpl< Scalar > &settings, const boost::optional< ConstRefVectorXs > &lambda_guess=boost::none)
Definition: expose-contact-inverse-dynamics.cpp:25
pinocchio::python::ConstRefVectorXs
const typedef Eigen::Ref< const VectorXs > ConstRefVectorXs
Definition: admm-solver.cpp:31
R
R
pinocchio::python::VectorXs
context::VectorXs VectorXs
Definition: admm-solver.cpp:30
pinocchio::python::Options
@ Options
Definition: expose-contact-inverse-dynamics.cpp:22
simulation-contact-dynamics.contact_datas
list contact_datas
Definition: simulation-contact-dynamics.py:60
pinocchio::context::VectorXs
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
Definition: context/generic.hpp:47
pinocchio::ProximalSettingsTpl
Structure containing all the settings parameters for the proximal algorithms.
Definition: algorithm/fwd.hpp:13
algorithms.hpp
python
pinocchio::python::v
const Vector3Like & v
Definition: bindings/python/spatial/explog.hpp:66
pinocchio::q
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
Definition: joint-configuration.hpp:1083
pinocchio::python::context::Options
@ Options
Definition: bindings/python/context/generic.hpp:40
a
Vec3f a
contact-inverse-dynamics.hpp
pinocchio::computeContactImpulses
const DataTpl< Scalar, Options, JointCollectionTpl >::TangentVectorType & computeContactImpulses(const ModelTpl< Scalar, Options, JointCollectionTpl > &model, DataTpl< Scalar, Options, JointCollectionTpl > &data, const Eigen::MatrixBase< VectorLikeC > &c_ref, const std::vector< RigidConstraintModelTpl< Scalar, Options >, ConstraintModelAllocator > &contact_models, std::vector< RigidConstraintDataTpl< Scalar, Options >, ConstraintDataAllocator > &contact_datas, const std::vector< CoulombFrictionConeTpl< Scalar >, CoulombFrictionConelAllocator > &cones, const Eigen::MatrixBase< VectorLikeR > &R, const Eigen::MatrixBase< VectorLikeGamma > &constraint_correction, ProximalSettingsTpl< Scalar > &settings, const boost::optional< VectorLikeImp > &impulse_guess=boost::none)
Compute the contact impulses given a target velocity of contact points.
Definition: contact-inverse-dynamics.hpp:56
contact-cholesky.contact_models
list contact_models
Definition: contact-cholesky.py:22
std-vector.hpp
pinocchio::ModelTpl
Definition: context/generic.hpp:20
cartpole.dt
float dt
Definition: cartpole.py:145
pinocchio::python::context::Scalar
PINOCCHIO_PYTHON_SCALAR_TYPE Scalar
Definition: bindings/python/context/generic.hpp:37
pinocchio::model
JointCollectionTpl & model
Definition: joint-configuration.hpp:1082
pinocchio
Main pinocchio namespace.
Definition: timings.cpp:27


pinocchio
Author(s):
autogenerated on Thu Dec 19 2024 03:41:29