aligator  0.10.0
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
11
12namespace aligator::python {
13using namespace ::aligator::dynamics;
15using context::MatrixXs;
18using context::Scalar;
19using context::VectorXs;
20using PolyManifold = xyz::polymorphic<context::Manifold>;
21
25using Vector3s = typename math_types<Scalar>::Vector3s;
27
28void exposeODEs() {
29 register_polymorphic_to_python<xyz::polymorphic<ODEAbstract>>();
31 ode_visitor;
32
33 bp::class_<PyODEAbstract<>, bp::bases<ContinuousDynamicsAbstract>,
34 boost::noncopyable>(
35 "ODEAbstract",
36 "Continuous dynamics described by ordinary differential equations "
37 "(ODEs).",
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)`.")
48 .def(ode_visitor);
49
50 bp::class_<LinearODETpl<Scalar>, bp::bases<ODEAbstract>>(
51 "LinearODE",
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 "
57 "assumed.",
58 bp::args("self", "A", "B", "c")))
59 .def_readonly("A", &LinearODETpl<Scalar>::A_, "State transition matrix.")
60 .def_readonly("B", &LinearODETpl<Scalar>::B_, "Control matrix.")
61 .def_readonly("c", &LinearODETpl<Scalar>::c_, "Constant drift term.")
62 .def(ode_visitor);
63
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,
68 const Vector3s &, const ContactMap &, const int>(
69 bp::args("self", "space", "total mass", "gravity", "contact_map",
70 "force_size")))
71 .def_readwrite("contact_map", &CentroidalFwdDynamics::contact_map_)
73 .def(ode_visitor);
74
75 bp::register_ptr_to_python<shared_ptr<CentroidalFwdDataTpl<Scalar>>>();
76 bp::class_<CentroidalFwdDataTpl<Scalar>, bp::bases<ODEData>>(
77 "CentroidalFwdData", bp::no_init);
78
79 bp::class_<ContinuousCentroidalFwdDynamics, bp::bases<ODEAbstract>>(
80 "ContinuousCentroidalFwdDynamics",
81 "Nonlinear centroidal dynamics with preplanned feet positions and smooth "
82 "forces",
83 bp::init<const proxsuite::nlp::VectorSpaceTpl<Scalar> &, const double,
84 const Vector3s &, const ContactMap &, const int>(
85 bp::args("self", "space", "total mass", "gravity", "contact_map",
86 "force_size")))
87 .def_readwrite("contact_map",
90 .def(ode_visitor);
91
92 bp::register_ptr_to_python<
93 shared_ptr<ContinuousCentroidalFwdDataTpl<Scalar>>>();
94 bp::class_<ContinuousCentroidalFwdDataTpl<Scalar>, bp::bases<ODEData>>(
95 "ContinuousCentroidalFwdData", bp::no_init);
96}
97} // namespace aligator::python
dynamics::ContinuousDynamicsDataTpl< Scalar > ODEData
Definition context.hpp:16
dynamics::ContinuousDynamicsAbstractTpl< Scalar > ContinuousDynamicsAbstract
Definition context.hpp:9
dynamics::ODEAbstractTpl< Scalar > ODEAbstract
Definition context.hpp:14
Namespace for modelling system dynamics.
The Python bindings.
Definition blk-matrix.hpp:5
typename math_types< Scalar >::Vector3s Vector3s
xyz::polymorphic< Manifold > PolyManifold
Nonlinear centroidal forward dynamics.
Definition fwd.hpp:26
Nonlinear centroidal forward dynamics with smooth control.
Definition fwd.hpp:31
Linear ordinary differential equation .