aligator  0.6.1
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
expose-stage.cpp
Go to the documentation of this file.
1
5
9
10#include <proxsuite-nlp/python/deprecation-policy.hpp>
11
12namespace aligator {
13namespace python {
14
18 using context::Scalar;
20 using StageData = StageDataTpl<Scalar>;
21
22 using CostPtr = shared_ptr<context::CostAbstract>;
23 using DynamicsPtr = shared_ptr<context::DynamicsModel>;
24 using FunctionPtr = shared_ptr<context::StageFunction>;
25 using CstrSetPtr = shared_ptr<ConstraintSet>;
26
27 StdVectorPythonVisitor<std::vector<shared_ptr<StageModel>>, true>::expose(
28 "StdVec_StageModel");
29
30#pragma GCC diagnostic push
31#pragma GCC diagnostic ignored "-Wdeprecated-declarations"
32 bp::register_ptr_to_python<shared_ptr<StageModel>>();
33 bp::class_<StageModel>(
34 "StageModel",
35 "A stage of the control problem. Holds costs, dynamics, and constraints.",
36 bp::init<CostPtr, DynamicsPtr>(bp::args("self", "cost", "dynamics")))
37 .def<void (StageModel::*)(const context::StageConstraint &)>(
38 "addConstraint", &StageModel::addConstraint,
39 bp::args("self", "constraint"),
40 "Add an existing constraint to the stage.")
41 .def<void (StageModel::*)(FunctionPtr, CstrSetPtr)>(
42 "addConstraint", &StageModel::addConstraint,
43 bp::args("self", "func", "cstr_set"),
44 "Constructs a new constraint (from the underlying function and set) "
45 "and adds it to the stage.")
46 .def_readonly("constraints", &StageModel::constraints_,
47 "Get the set of constraints.")
48 .def_readonly("dynamics", &StageModel::dynamics_, "Stage dynamics.")
49 .add_property("xspace",
50 bp::make_function(&StageModel::xspace,
51 bp::return_internal_reference<>()),
52 "State space for the current state :math:`x_k`.")
53 .add_property("xspace_next",
54 bp::make_function(&StageModel::xspace_next,
55 bp::return_internal_reference<>()),
56 "State space corresponding to next state :math:`x_{k+1}`.")
57 .add_property("uspace",
58 bp::make_function(&StageModel::uspace,
59 bp::return_internal_reference<>()),
60 "Control space.")
61 .add_property("cost",
62 bp::make_function(&StageModel::cost,
63 bp::return_internal_reference<>()),
64 "Stage cost.")
65 .add_property(
66 "dyn_model",
67 bp::make_function(&StageModel::dyn_model,
68 proxsuite::nlp::deprecation_warning_policy<
69 proxsuite::nlp::DeprecationType::DEPRECATION,
70 bp::return_internal_reference<>>(
71 "Deprecated. Use StageModel.dynamics instead")),
72 "Stage dynamics.")
73 .def("evaluate", &StageModel::evaluate,
74 bp::args("self", "x", "u", "y", "data"),
75 "Evaluate the stage cost, dynamics, constraints.")
76 .def("computeFirstOrderDerivatives",
77 &StageModel::computeFirstOrderDerivatives,
78 bp::args("self", "x", "u", "y", "data"),
79 "Compute gradients of the stage cost and jacobians of the dynamics "
80 "and "
81 "constraints.")
82 .def("computeSecondOrderDerivatives",
83 &StageModel::computeSecondOrderDerivatives,
84 bp::args("self", "x", "u", "data"),
85 "Compute Hessians of the stage cost.")
86 .add_property("ndx1", &StageModel::ndx1)
87 .add_property("ndx2", &StageModel::ndx2)
88 .add_property("nu", &StageModel::nu, "Control space dimension.")
89 .add_property("num_primal", &StageModel::numPrimal,
90 "Number of primal variables.")
91 .add_property("num_dual", &StageModel::numDual,
92 "Number of dual variables.")
93 .def(CreateDataPythonVisitor<StageModel>())
94 .def(ClonePythonVisitor<StageModel>())
95 .def(PrintableVisitor<StageModel>());
96#pragma GCC diagnostic pop
97
98 bp::register_ptr_to_python<shared_ptr<StageData>>();
99 StdVectorPythonVisitor<std::vector<shared_ptr<StageData>>, true>::expose(
100 "StdVec_StageData");
101
102 bp::class_<StageData>("StageData", "Data struct for StageModel objects.",
103 bp::init<const StageModel &>())
104 .def_readonly("cost_data", &StageData::cost_data)
105 .def_readwrite("dynamics_data", &StageData::dynamics_data)
106 .def_readwrite("constraint_data", &StageData::constraint_data)
107 .def(ClonePythonVisitor<StageData>());
108}
109
110} // namespace python
111} // namespace aligator
ConstraintSetBase< Scalar > ConstraintSet
Definition context.hpp:22
ManifoldAbstractTpl< Scalar > Manifold
Definition context.hpp:14
StageConstraintTpl< Scalar > StageConstraint
Definition context.hpp:20
void exposeStage()
Expose StageModel and StageData.
shared_ptr< StageFunction > FunctionPtr
shared_ptr< CostAbstract > CostPtr
Main package namespace.