aligator  0.14.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
expose-composite-costs.cpp
Go to the documentation of this file.
3
7
8namespace aligator {
9namespace python {
10using context::ConstMatrixRef;
11using context::ConstVectorRef;
15using context::MatrixXs;
16using context::Scalar;
18using PolyFunction = xyz::polymorphic<StageFunction>;
19using PolyManifold = xyz::polymorphic<Manifold>;
21
23
24 using CompositeData = CompositeCostDataTpl<Scalar>;
25 using QuadStateCost = QuadraticStateCostTpl<Scalar>;
26 using QuadControlCost = QuadraticControlCostTpl<Scalar>;
27 using LogResCost = LogResidualCostTpl<Scalar>;
28 using RelaxedLogCost = RelaxedLogBarrierCostTpl<Scalar>;
29
31 bp::class_<QuadResCost, bp::bases<CostAbstract>>(
32 "QuadraticResidualCost", "Weighted 2-norm of a given residual function.",
33 bp::init<PolyManifold, PolyFunction, const ConstMatrixRef &>(
34 bp::args("self", "space", "function", "weights")))
35 .def_readwrite("residual", &QuadResCost::residual_)
36 .def_readwrite("weights", &QuadResCost::weights_)
38 .def(visitor);
39
40 bp::class_<LogResCost, bp::bases<CostAbstract>>(
41 "LogResidualCost", "Weighted log-cost composite cost.",
42 bp::init<PolyManifold, PolyFunction, const ConstVectorRef &>(
43 bp::args("self", "space", "function", "barrier_weights")))
44 .def(bp::init<PolyManifold, PolyFunction, Scalar>(
45 bp::args("self", "function", "scale")))
46 .def_readwrite("residual", &LogResCost::residual_)
47 .def_readwrite("weights", &LogResCost::barrier_weights_)
49 .def(visitor);
50
51 bp::class_<RelaxedLogCost, bp::bases<CostAbstract>>(
52 "RelaxedLogBarrierCost", "Relaxed log-barrier composite cost.",
53 bp::init<PolyManifold, PolyFunction, const ConstVectorRef &,
54 const Scalar>(
55 bp::args("self", "space", "function", "weights", "threshold")))
56 .def(bp::init<PolyManifold, PolyFunction, const Scalar, const Scalar>(
57 bp::args("self", "space", "function", "weights", "threshold")))
58 .def_readwrite("residual", &RelaxedLogCost::residual_)
59 .def_readwrite("weights", &RelaxedLogCost::barrier_weights_)
61 .def(visitor);
62
63 bp::class_<CompositeData, bp::bases<CostData>>(
64 "CompositeCostData",
65 bp::init<int, int, shared_ptr<context::StageFunctionData>>(
66 bp::args("self", "ndx", "nu", "rdata")))
67 .def_readwrite("residual_data", &CompositeData::residual_data);
68
69 bp::class_<QuadStateCost, bp::bases<QuadResCost>>(
70 "QuadraticStateCost",
71 "Quadratic distance over the state manifold. This is a shortcut to "
72 "create a `QuadraticResidualCost` over a state error residual.",
73 bp::no_init)
74 .def(bp::init<QuadStateCost::StateError &, const MatrixXs &>(
75 bp::args("self", "resdl", "weights")))
76 .def(bp::init<PolyManifold, const int, const ConstVectorRef &,
77 const MatrixXs &>(
78 bp::args("self", "space", "nu", "target", "weights")))
79 .add_property("target", &QuadStateCost::getTarget,
80 &QuadStateCost::setTarget,
81 "Target of the quadratic distance.")
82 .def(visitor);
83
84 bp::class_<QuadControlCost, bp::bases<QuadResCost>>(
85 "QuadraticControlCost", "Quadratic control cost.", bp::no_init)
86 .def(bp::init<PolyManifold, ConstVectorRef, const MatrixXs &>(
87 bp::args("space", "target", "weights")))
88 .def(bp::init<PolyManifold, QuadControlCost::ControlError,
89 const ConstMatrixRef &>(
90 bp::args("self", "space", "resdl", "weights")))
91 .def(bp::init<PolyManifold, int, const MatrixXs &>(
92 bp::args("space", "nu", "weights")))
93 .add_property("target", &QuadControlCost::getTarget,
94 &QuadControlCost::setTarget,
95 "Reference of the control cost.")
96 .def(visitor);
97}
98} // namespace python
99} // namespace aligator
CostAbstractTpl< Scalar > CostAbstract
Definition context.hpp:26
ManifoldAbstractTpl< Scalar > Manifold
Definition context.hpp:14
StageFunctionTpl< Scalar > StageFunction
Definition context.hpp:17
CostDataAbstractTpl< Scalar > CostData
Definition context.hpp:27
The Python bindings.
Definition blk-matrix.hpp:5
xyz::polymorphic< StageFunction > PolyFunction
xyz::polymorphic< Manifold > PolyManifold
void exposeComposites()
Composite cost functions.
QuadraticResidualCostTpl< Scalar > QuadResCost
Main package namespace.
Data struct for composite costs.
Log-barrier of an underlying cost function.
Quadratic composite of an underlying function.
xyz::polymorphic< StageFunction > residual_
Quadratic distance cost over the state manifold.
Log-barrier of an underlying cost function.