23 using Manifold = proxsuite::nlp::MultibodyPhaseSpace<Scalar>;
24 using Vector3s =
typename math_types<Scalar>::Vector3s;
26 using Model = pinocchio::ModelTpl<Scalar>;
31 bp::class_<KinodynamicsFwdDynamics, bp::bases<ODEAbstract>>(
32 "KinodynamicsFwdDynamics",
33 "Centroidal forward dynamics + kinematics using Pinocchio.",
34 bp::init<
const Manifold &,
const Model &,
const Vector3s &,
35 const std::vector<bool> &,
36 const std::vector<pinocchio::FrameIndex> &,
const int>(
38 bp::args(
"self",
"space",
"model",
"gravity",
"contact_states",
39 "contact_ids",
"force_size")))
40 .def_readwrite(
"contact_states",
41 &KinodynamicsFwdDynamics::contact_states_)
44 bp::register_ptr_to_python<shared_ptr<KinodynamicsFwdData>>();
46 bp::class_<KinodynamicsFwdData, bp::bases<ODEData>>(
"KinodynamicsFwdData",
48 .def_readwrite(
"pin_data", &KinodynamicsFwdData::pin_data_);