aligator  0.9.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
continuous.hpp
Go to the documentation of this file.
1
3#pragma once
4
6
10
11#include "proxsuite-nlp/python/polymorphic.hpp"
12
13namespace aligator {
14namespace python {
15
16template <class T = context::ContinuousDynamicsAbstract>
18 : T,
19 proxsuite::nlp::python::PolymorphicWrapper<PyContinuousDynamics<T>, T> {
22 using T::T;
23
24 void evaluate(const ConstVectorRef &x, const ConstVectorRef &u,
25 const ConstVectorRef &xdot, Data &data) const override {
26 ALIGATOR_PYTHON_OVERRIDE_PURE(void, "evaluate", x, u, xdot,
27 boost::ref(data));
28 }
29
30 void computeJacobians(const ConstVectorRef &x, const ConstVectorRef &u,
31 const ConstVectorRef &xdot, Data &data) const override {
32 ALIGATOR_PYTHON_OVERRIDE_PURE(void, "computeJacobians", x, u, xdot,
33 boost::ref(data));
34 }
35
36 shared_ptr<Data> createData() const override {
37 ALIGATOR_PYTHON_OVERRIDE(shared_ptr<Data>, T, createData, );
38 }
39
40 shared_ptr<Data> default_createData() const { return T::createData(); }
41};
42
43template <class T = context::ODEAbstract>
44struct PyODEAbstract final
45 : T,
46 proxsuite::nlp::python::PolymorphicWrapper<PyODEAbstract<T>, T> {
50
51 using T::T;
52
53 void forward(const ConstVectorRef &x, const ConstVectorRef &u,
54 Data &data) const override {
55 ALIGATOR_PYTHON_OVERRIDE_PURE(void, "forward", x, u, boost::ref(data));
56 }
57
58 void dForward(const ConstVectorRef &x, const ConstVectorRef &u,
59 Data &data) const override {
60 ALIGATOR_PYTHON_OVERRIDE_PURE(void, "dForward", x, u, boost::ref(data));
61 }
62
63 shared_ptr<Data> createData() const override {
64 ALIGATOR_PYTHON_OVERRIDE(shared_ptr<Data>, T, createData, );
65 }
66
67 shared_ptr<Data> default_createData() const { return T::createData(); }
68};
69
70} // namespace python
71} // namespace aligator
72//
73namespace boost::python::objects {
74
75template <>
76struct value_holder<aligator::python::PyContinuousDynamics<>>
77 : proxsuite::nlp::python::OwningNonOwningHolder<
78 aligator::python::PyContinuousDynamics<>> {
79 using OwningNonOwningHolder::OwningNonOwningHolder;
80};
81
82template <>
83struct value_holder<aligator::python::PyODEAbstract<>>
84 : proxsuite::nlp::python::OwningNonOwningHolder<
85 aligator::python::PyODEAbstract<>> {
86 using OwningNonOwningHolder::OwningNonOwningHolder;
87};
88
89} // namespace boost::python::objects
#define ALIGATOR_PYTHON_OVERRIDE(ret_type, cname, fname,...)
Define the body of a virtual function override. This is meant to reduce boilerplate code when exposin...
Definition macros.hpp:45
#define ALIGATOR_PYTHON_OVERRIDE_PURE(ret_type, pyname,...)
Define the body of a virtual function override. This is meant to reduce boilerplate code when exposin...
Definition macros.hpp:37
Base definitions for continuous dynamics.
dynamics::ContinuousDynamicsDataTpl< Scalar > ODEData
Definition context.hpp:16
dynamics::ContinuousDynamicsDataTpl< Scalar > ContinuousDynamicsData
Definition context.hpp:12
Main package namespace.
Defines a class representing ODEs.
Data struct for ContinuousDynamicsAbstractTpl.
Definition fwd.hpp:15
void evaluate(const ConstVectorRef &x, const ConstVectorRef &u, const ConstVectorRef &xdot, Data &data) const override
Evaluate the vector field at a point .
shared_ptr< Data > createData() const override
Create a data holder instance.
void computeJacobians(const ConstVectorRef &x, const ConstVectorRef &u, const ConstVectorRef &xdot, Data &data) const override
Differentiate the vector field.
shared_ptr< Data > default_createData() const
void forward(const ConstVectorRef &x, const ConstVectorRef &u, Data &data) const override
Evaluate the ODE vector field: this returns the value of .
shared_ptr< Data > createData() const override
Create a data holder instance.
shared_ptr< Data > default_createData() const
void dForward(const ConstVectorRef &x, const ConstVectorRef &u, Data &data) const override
Evaluate the vector field Jacobians.