21 bp::register_ptr_to_python<shared_ptr<ODEAbstract>>();
22 bp::class_<PyODEAbstract<>, bp::bases<ContinuousDynamicsAbstract>,
25 "Continuous dynamics described by ordinary differential equations "
27 bp::init<const ManifoldPtr &, int>(bp::args(
"self",
"space",
"nu")))
28 .def(
"forward", bp::pure_virtual(&ODEAbstract::forward),
29 bp::args(
"self",
"x",
"u",
"data"),
30 "Compute the value of the ODE vector field, i.e. the "
31 "state time derivative :math:`\\dot{x}`.")
32 .def(
"dForward", bp::pure_virtual(&ODEAbstract::dForward),
33 bp::args(
"self",
"x",
"u",
"data"),
34 "Compute the derivatives of the ODE vector field with respect "
35 "to the state-control pair :math:`(x, u)`.")
38 bp::class_<LinearODETpl<Scalar>, bp::bases<ODEAbstract>>(
40 "Linear ordinary differential equation, :math:`\\dot{x} = Ax + Bu`.",
41 bp::init<ManifoldPtr, MatrixXs, MatrixXs, VectorXs>(
42 bp::args(
"self",
"A",
"B",
"c")))
43 .def(bp::init<MatrixXs, MatrixXs, VectorXs>(
44 "Constructor with just the matrices; a Euclidean state space is "
46 bp::args(
"self",
"A",
"B",
"c")))
47 .def_readonly(
"A", &LinearODETpl<Scalar>::A_,
"State transition matrix.")
48 .def_readonly(
"B", &LinearODETpl<Scalar>::B_,
"Control matrix.")
49 .def_readonly(
"c", &LinearODETpl<Scalar>::c_,
"Constant drift term.");
dynamics::ContinuousDynamicsAbstractTpl< Scalar > ContinuousDynamicsAbstract
dynamics::ODEDataTpl< Scalar > ODEData
dynamics::ODEAbstractTpl< Scalar > ODEAbstract