Go to the documentation of this file.
5 #define BOOST_PYTHON_MAX_ARITY 24
16 #ifndef PINOCCHIO_PYTHON_SKIP_ALGORITHM_CONSTRAINED_DYNAMICS
31 const context::CoulombFrictionConeVector & cones,
35 const boost::optional<ConstRefVectorXs> & lambda_guess = boost::none)
39 settings, lambda_guess);
51 const context::CoulombFrictionConeVector & cones,
55 const boost::optional<ConstRefVectorXs> & lambda_guess = boost::none)
58 model,
data,
q,
v,
a,
dt,
contact_models,
contact_datas, cones,
R, constraint_correction,
59 settings, lambda_guess);
61 #endif // PINOCCHIO_PYTHON_SKIP_ALGORITHM_CONSTRAINED_DYNAMICS
65 #ifndef PINOCCHIO_PYTHON_SKIP_ALGORITHM_CONSTRAINED_DYNAMICS
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 "
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");
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 "
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
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)
void exposeContactInverseDynamics()
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,...
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)
const typedef Eigen::Ref< const VectorXs > ConstRefVectorXs
context::VectorXs VectorXs
Eigen::Matrix< Scalar, Eigen::Dynamic, 1, Options > VectorXs
Structure containing all the settings parameters for the proximal algorithms.
JointCollectionTpl const Eigen::MatrixBase< ConfigVectorType > & q
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.
PINOCCHIO_PYTHON_SCALAR_TYPE Scalar
JointCollectionTpl & model
Main pinocchio namespace.
pinocchio
Author(s):
autogenerated on Fri Nov 1 2024 02:41:43