17 using ODEData = ODEDataTpl<Scalar>;
18 using ODEAbstract = ODEAbstractTpl<Scalar>;
19 using KinodynamicsFwdData = KinodynamicsFwdDataTpl<Scalar>;
20 using KinodynamicsFwdDynamics = KinodynamicsFwdDynamicsTpl<Scalar>;
21 using Manifold = proxsuite::nlp::MultibodyPhaseSpace<Scalar>;
23 using Vector3s =
typename math_types<Scalar>::Vector3s;
25 using Model = pinocchio::ModelTpl<Scalar>;
27 bp::class_<KinodynamicsFwdDynamics, bp::bases<ODEAbstract>>(
28 "KinodynamicsFwdDynamics",
29 "Centroidal forward dynamics + kinematics using Pinocchio.",
31 const std::vector<bool> &,
32 const std::vector<pinocchio::FrameIndex> &,
const int>(
34 bp::args(
"self",
"space",
"model",
"gravity",
"contact_states",
35 "contact_ids",
"force_size")))
36 .def_readwrite(
"contact_states",
37 &KinodynamicsFwdDynamics::contact_states_);
39 bp::register_ptr_to_python<shared_ptr<KinodynamicsFwdData>>();
41 bp::class_<KinodynamicsFwdData, bp::bases<ODEData>>(
"KinodynamicsFwdData",
43 .def_readwrite(
"pin_data", &KinodynamicsFwdData::pin_data_);