29 register_polymorphic_to_python<xyz::polymorphic<ODEAbstract>>();
33 bp::class_<PyODEAbstract<>, bp::bases<ContinuousDynamicsAbstract>,
36 "Continuous dynamics described by ordinary differential equations "
38 bp::init<const PolyManifold &, int>(bp::args(
"self",
"space",
"nu")))
39 .def(
"forward", bp::pure_virtual(&ODEAbstract::forward),
40 bp::args(
"self",
"x",
"u",
"data"),
41 "Compute the value of the ODE vector field, i.e. the "
42 "state time derivative :math:`\\dot{x}`.")
43 .def(
"dForward", bp::pure_virtual(&ODEAbstract::dForward),
44 bp::args(
"self",
"x",
"u",
"data"),
45 "Compute the derivatives of the ODE vector field with respect "
46 "to the state-control pair :math:`(x, u)`.")
50 bp::class_<LinearODETpl<Scalar>, bp::bases<ODEAbstract>>(
52 "Linear ordinary differential equation, :math:`\\dot{x} = Ax + Bu`.",
53 bp::init<PolyManifold, MatrixXs, MatrixXs, VectorXs>(
54 bp::args(
"self",
"A",
"B",
"c")))
55 .def(bp::init<MatrixXs, MatrixXs, VectorXs>(
56 "Constructor with just the matrices; a Euclidean state space is "
58 bp::args(
"self",
"A",
"B",
"c")))
64 bp::class_<CentroidalFwdDynamics, bp::bases<ODEAbstract>>(
65 "CentroidalFwdDynamics",
66 "Nonlinear centroidal dynamics with preplanned feet positions",
67 bp::init<const proxsuite::nlp::VectorSpaceTpl<Scalar> &,
const double,
69 bp::args(
"self",
"space",
"total mass",
"gravity",
"contact_map",
75 bp::register_ptr_to_python<shared_ptr<CentroidalFwdDataTpl<Scalar>>>();
76 bp::class_<CentroidalFwdDataTpl<Scalar>, bp::bases<ODEData>>(
77 "CentroidalFwdData", bp::no_init);
79 bp::class_<ContinuousCentroidalFwdDynamics, bp::bases<ODEAbstract>>(
80 "ContinuousCentroidalFwdDynamics",
81 "Nonlinear centroidal dynamics with preplanned feet positions and smooth "
83 bp::init<const proxsuite::nlp::VectorSpaceTpl<Scalar> &,
const double,
85 bp::args(
"self",
"space",
"total mass",
"gravity",
"contact_map",
87 .def_readwrite(
"contact_map",
92 bp::register_ptr_to_python<
93 shared_ptr<ContinuousCentroidalFwdDataTpl<Scalar>>>();
94 bp::class_<ContinuousCentroidalFwdDataTpl<Scalar>, bp::bases<ODEData>>(
95 "ContinuousCentroidalFwdData", bp::no_init);
dynamics::ContinuousDynamicsDataTpl< Scalar > ODEData
dynamics::ContinuousDynamicsAbstractTpl< Scalar > ContinuousDynamicsAbstract
dynamics::ODEAbstractTpl< Scalar > ODEAbstract