18 using proxsuite::nlp::MultibodyPhaseSpace;
20 using StateManifold = MultibodyPhaseSpace<Scalar>;
25 bp::class_<MultibodyFreeFwdDynamics, bp::bases<ODEAbstract>>(
26 "MultibodyFreeFwdDynamics",
27 "Free-space forward dynamics on multibodies using Pinocchio's ABA "
29 bp::init<StateManifold, const context::MatrixXs &>(
30 "Constructor where the actuation matrix is provided.",
31 (
"self"_a,
"space",
"actuation_matrix")))
32 .def(bp::init<StateManifold>(
33 "Constructor without actuation matrix (assumed to be the (nu,nu) "
36 .add_property(
"ntau", &MultibodyFreeFwdDynamics::ntau,
39 "isUnderactuated", &MultibodyFreeFwdDynamics::isUnderactuated,
40 "Whether the system is underactuated, i.e. if the actuation matrix "
41 "rank is lower than the acceleration vector's dimension.")
42 .add_property(
"actuationMatrixRank",
43 &MultibodyFreeFwdDynamics::getActuationMatrixRank,
44 "Get the rank of the actuation matrix.")
47 bp::register_ptr_to_python<shared_ptr<MultibodyFreeFwdData>>();
49 bp::class_<MultibodyFreeFwdData, bp::bases<ODEData>>(
"MultibodyFreeFwdData",
51 .def_readwrite(
"tau", &MultibodyFreeFwdData::tau_)
52 .def_readwrite(
"dtau_dx", &MultibodyFreeFwdData::dtau_dx_)
53 .def_readwrite(
"dtau_du", &MultibodyFreeFwdData::dtau_du_)
54 .def_readwrite(
"pin_data", &MultibodyFreeFwdData::pin_data_);
Free-space multibody forward dynamics, using Pinocchio.