32 using MultibodyConstraintFwdDynamics =
37 bp::class_<MultibodyConstraintFwdDynamics, bp::bases<ODEAbstract>>(
38 "MultibodyConstraintFwdDynamics",
39 "Constraint forward dynamics using Pinocchio.",
40 bp::init<const MultibodyPhaseSpace<Scalar> &,
const context::MatrixXs &,
41 const RigidConstraintModelVector &,
42 const pinocchio::ProximalSettingsTpl<Scalar> &>(
43 (
"self"_a,
"space",
"actuation_matrix",
"constraint_models",
46 .def_readwrite(
"constraint_models",
47 &MultibodyConstraintFwdDynamics::constraint_models_)
48 .add_property(
"ntau", &MultibodyConstraintFwdDynamics::ntau,
51 bp::register_ptr_to_python<shared_ptr<MultibodyConstraintFwdData>>();
53 bp::class_<MultibodyConstraintFwdData, bp::bases<ODEData>>(
54 "MultibodyConstraintFwdData", bp::no_init)
55 .def_readwrite(
"tau", &MultibodyConstraintFwdData::tau_)
56 .def_readwrite(
"dtau_dx", &MultibodyConstraintFwdData::dtau_dx_)
57 .def_readwrite(
"dtau_du", &MultibodyConstraintFwdData::dtau_du_)
58 .def_readwrite(
"pin_data", &MultibodyConstraintFwdData::pin_data_)
59 .def_readwrite(
"constraint_datas",
60 &MultibodyConstraintFwdData::constraint_datas_);
dynamics::ContinuousDynamicsDataTpl< Scalar > ODEData
dynamics::ContinuousDynamicsAbstractTpl< Scalar > ContinuousDynamicsAbstract
dynamics::ODEAbstractTpl< Scalar > ODEAbstract
Constraint multibody forward dynamics, using Pinocchio.