aligator  0.6.1
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
expose-ode.cpp
Go to the documentation of this file.
1
3
8
9namespace aligator::python {
11using context::MatrixXs;
14using context::Scalar;
15using context::VectorXs;
16using ManifoldPtr = shared_ptr<context::Manifold>;
17
18void exposeODEs() {
20
21 bp::register_ptr_to_python<shared_ptr<ODEAbstract>>();
22 bp::class_<PyODEAbstract<>, bp::bases<ContinuousDynamicsAbstract>,
23 boost::noncopyable>(
24 "ODEAbstract",
25 "Continuous dynamics described by ordinary differential equations "
26 "(ODEs).",
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)`.")
36 .def(CreateDataPolymorphicPythonVisitor<ODEAbstract, PyODEAbstract<>>());
37
38 bp::class_<LinearODETpl<Scalar>, bp::bases<ODEAbstract>>(
39 "LinearODE",
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 "
45 "assumed.",
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.");
50}
51} // namespace aligator::python
dynamics::ContinuousDynamicsAbstractTpl< Scalar > ContinuousDynamicsAbstract
Definition context.hpp:9
dynamics::ODEDataTpl< Scalar > ODEData
Definition context.hpp:16
dynamics::ODEAbstractTpl< Scalar > ODEAbstract
Definition context.hpp:14
The Python bindings.
Definition blk-matrix.hpp:5
shared_ptr< Manifold > ManifoldPtr
Linear ordinary differential equation .