aligator  0.10.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
30 bp::class_<QuadResCost, bp::bases<CostAbstract>>(
31 "QuadraticResidualCost", "Weighted 2-norm of a given residual function.",
32 bp::init<PolyManifold, PolyFunction, const ConstMatrixRef &>(
33 bp::args("self", "space", "function", "weights")))
34 .def_readwrite("residual", &QuadResCost::residual_)
35 .def_readwrite("weights", &QuadResCost::weights_)
37 .def(visitor);
38
39 bp::class_<LogResCost, bp::bases<CostAbstract>>(
40 "LogResidualCost", "Weighted log-cost composite cost.",
41 bp::init<PolyManifold, PolyFunction, const ConstVectorRef &>(
42 bp::args("self", "space", "function", "barrier_weights")))
43 .def(bp::init<PolyManifold, PolyFunction, Scalar>(
44 bp::args("self", "function", "scale")))
45 .def_readwrite("residual", &LogResCost::residual_)
46 .def_readwrite("weights", &LogResCost::barrier_weights_)
48 .def(visitor);
49
50 bp::class_<CompositeData, bp::bases<CostData>>(
51 "CompositeCostData",
52 bp::init<int, int, shared_ptr<context::StageFunctionData>>(
53 bp::args("self", "ndx", "nu", "rdata")))
54 .def_readwrite("residual_data", &CompositeData::residual_data);
55
56 bp::class_<QuadStateCost, bp::bases<QuadResCost>>(
57 "QuadraticStateCost",
58 "Quadratic distance over the state manifold. This is a shortcut to "
59 "create a `QuadraticResidualCost` over a state error residual.",
60 bp::no_init)
61 .def(bp::init<QuadStateCost::StateError &, const MatrixXs &>(
62 bp::args("self", "resdl", "weights")))
63 .def(bp::init<PolyManifold, const int, const ConstVectorRef &,
64 const MatrixXs &>(
65 bp::args("self", "space", "nu", "target", "weights")))
66 .add_property("target", &QuadStateCost::getTarget,
67 &QuadStateCost::setTarget,
68 "Target of the quadratic distance.")
69 .def(visitor);
70
71 bp::class_<QuadControlCost, bp::bases<QuadResCost>>(
72 "QuadraticControlCost", "Quadratic control cost.", bp::no_init)
73 .def(bp::init<PolyManifold, ConstVectorRef, const MatrixXs &>(
74 bp::args("space", "target", "weights")))
75 .def(bp::init<PolyManifold, QuadControlCost::Error, const MatrixXs &>(
76 bp::args("self", "space", "resdl", "weights")))
77 .def(bp::init<PolyManifold, int, const MatrixXs &>(
78 bp::args("space", "nu", "weights")))
79 .add_property("target", &QuadControlCost::getTarget,
80 &QuadControlCost::setTarget,
81 "Reference of the control cost.")
82 .def(visitor);
83}
84} // namespace python
85} // namespace aligator
CostAbstractTpl< Scalar > CostAbstract
Definition context.hpp:25
ManifoldAbstractTpl< Scalar > Manifold
Definition context.hpp:14
StageFunctionTpl< Scalar > StageFunction
Definition context.hpp:16
CostDataAbstractTpl< Scalar > CostData
Definition context.hpp:26
xyz::polymorphic< StageFunction > PolyFunction
void exposeComposites()
Composite cost functions.
xyz::polymorphic< Manifold > PolyManifold
Main package namespace.
Data struct for composite costs.
Log-barrier of an underlying cost function.
xyz::polymorphic< StageFunction > residual_
Quadratic distance cost over the state manifold.