aligator  0.10.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
expose-solver-prox.cpp
Go to the documentation of this file.
1
6
8
9#include <eigenpy/std-unique-ptr.hpp>
10#include <eigenpy/variant.hpp>
11
12namespace aligator {
13namespace python {
14
16 using context::ConstVectorRef;
17 using context::Results;
18 using context::Scalar;
20 using context::VectorRef;
22
23 using LsOptions = Linesearch<Scalar>::Options;
24 eigenpy::register_symbolic_link_to_registered_type<LsOptions>();
25 eigenpy::register_symbolic_link_to_registered_type<LinesearchStrategy>();
26 eigenpy::register_symbolic_link_to_registered_type<
27 proxsuite::nlp::LSInterpolation>();
28
29 bp::enum_<LQSolverChoice>("LQSolverChoice")
30 .value("LQ_SOLVER_SERIAL", LQSolverChoice::SERIAL)
31 .value("LQ_SOLVER_PARALLEL", LQSolverChoice::PARALLEL)
32 .value("LQ_SOLVER_STAGEDENSE", LQSolverChoice::STAGEDENSE)
33 .export_values();
34
35 bp::class_<Workspace, bp::bases<WorkspaceBaseTpl<Scalar>>,
36 boost::noncopyable>(
37 "Workspace", "Workspace for ProxDDP.",
38 bp::init<const TrajOptProblem &>(("self"_a, "problem")))
39 .def_readonly("lqr_problem", &Workspace::lqr_problem,
40 "Buffers for the LQ subproblem.")
41 .def_readonly("Lxs", &Workspace::Lxs)
42 .def_readonly("Lus", &Workspace::Lus)
43 .def_readonly("Lds", &Workspace::Lds)
44 .def_readonly("Lvs", &Workspace::Lvs)
45 .def_readonly("dxs", &Workspace::dxs)
46 .def_readonly("dus", &Workspace::dus)
47 .def_readonly("dvs", &Workspace::dvs)
48 .def_readonly("dlams", &Workspace::dlams)
49 .def_readonly("trial_vs", &Workspace::trial_vs)
50 .def_readonly("trial_lams", &Workspace::trial_lams)
51 .def_readonly("lams_plus", &Workspace::lams_plus)
52 .def_readonly("lams_pdal", &Workspace::lams_pdal)
53 .def_readonly("vs_plus", &Workspace::vs_plus)
54 .def_readonly("vs_pdal", &Workspace::vs_pdal)
55 .def_readonly("shifted_constraints", &Workspace::shifted_constraints)
56 .def_readonly("cstr_proj_jacs", &Workspace::cstr_proj_jacs)
57 .def_readonly("inner_crit", &Workspace::inner_criterion)
58 .def_readonly("active_constraints", &Workspace::active_constraints)
59 .def_readonly("prev_xs", &Workspace::prev_xs)
60 .def_readonly("prev_us", &Workspace::prev_us)
61 .def_readonly("prev_lams", &Workspace::prev_lams)
62 .def_readonly("prev_vs", &Workspace::prev_vs)
63 .def_readonly("stage_infeasibilities", &Workspace::stage_infeasibilities)
64 .def_readonly("state_dual_infeas", &Workspace::state_dual_infeas)
65 .def_readonly("control_dual_infeas", &Workspace::control_dual_infeas)
67
68 bp::class_<Results, bp::bases<ResultsBaseTpl<Scalar>>, boost::noncopyable>(
69 "Results", "Results struct for proxDDP.",
70 bp::init<const TrajOptProblem &>(("self"_a, "problem")))
71 .def("cycleAppend", &Results::cycleAppend, ("self"_a, "problem", "x0"),
72 "Cycle the results.")
73 .def_readonly("al_iter", &Results::al_iter)
74 .def_readonly("lams", &Results::lams)
76
77 using SolverType = SolverProxDDPTpl<Scalar>;
78 using ls_variant_t = SolverType::LinesearchVariant::variant_t;
79
80 auto cls =
81 bp::class_<SolverType, boost::noncopyable>(
82 "SolverProxDDP",
83 "A proximal, augmented Lagrangian solver, using a DDP-type scheme to "
84 "compute "
85 "search directions and feedforward, feedback gains."
86 " The solver instance initializes both a Workspace and a Results "
87 "struct.",
88 bp::init<const Scalar, const Scalar, std::size_t, VerboseLevel,
90 ("self"_a, "tol", "mu_init"_a = 1e-2, "max_iters"_a = 1000,
91 "verbose"_a = VerboseLevel::QUIET,
93 "hess_approx"_a = HessianApprox::GAUSS_NEWTON)))
94 .def("cycleProblem", &SolverType::cycleProblem,
95 ("self"_a, "problem", "data"),
96 "Cycle the problem data (for MPC applications).")
97 .def_readwrite("bcl_params", &SolverType::bcl_params,
98 "BCL parameters.")
99 .def_readwrite("max_refinement_steps",
100 &SolverType::max_refinement_steps_)
101 .def_readwrite("refinement_threshold",
102 &SolverType::refinement_threshold_)
103 .def_readwrite("linear_solver_choice",
104 &SolverType::linear_solver_choice)
105 .def_readwrite("multiplier_update_mode",
106 &SolverType::multiplier_update_mode)
107 .def_readwrite("mu_init", &SolverType::mu_init,
108 "Initial AL penalty parameter.")
109 .add_property("mu", &SolverType::mu)
110 .def_readwrite(
111 "rollout_max_iters", &SolverType::rollout_max_iters,
112 "Maximum number of iterations when solving the forward dynamics.")
113 .def_readwrite("max_al_iters", &SolverType::max_al_iters,
114 "Maximum number of AL iterations.")
115 .def_readwrite("ls_mode", &SolverType::ls_mode, "Linesearch mode.")
116 .def_readwrite("sa_strategy", &SolverType::sa_strategy_,
117 "StepAcceptance strategy.")
118 .def_readwrite("rollout_type", &SolverType::rollout_type_,
119 "Rollout type.")
120 .def_readwrite("dual_weight", &SolverType::dual_weight,
121 "Dual penalty weight.")
122 .def_readwrite("reg_min", &SolverType::reg_min,
123 "Minimum regularization value.")
124 .def_readwrite("reg_max", &SolverType::reg_max,
125 "Maximum regularization value.")
126 .def("updateLQSubproblem", &SolverType::updateLQSubproblem, "self"_a)
127 .def("computeCriterion", &SolverType::computeCriterion, "self"_a,
128 "Compute problem stationarity.")
129 .add_property("linearSolver",
130 bp::make_getter(&SolverType::linearSolver_,
131 eigenpy::ReturnInternalStdUniquePtr{}),
132 "Linear solver for the semismooth Newton method.")
133 .def_readwrite("filter", &SolverType::filter_,
134 "Pair filter used to accept a step.")
135 .def("computeInfeasibilities", &SolverType::computeInfeasibilities,
136 ("self"_a, "problem"), "Compute problem infeasibilities.")
137 .add_property("num_threads", &SolverType::getNumThreads)
138 .def("setNumThreads", &SolverType::setNumThreads,
139 ("self"_a, "num_threads"))
140 .add_property("target_dual_tol", &SolverType::getDualTolerance)
141 .def("setDualTolerance", &SolverType::setDualTolerance,
142 ("self"_a, "tol"),
143 "Manually set the solver's dual infeasibility tolerance. Once "
144 "this method is called, the dual tolerance and primal tolerance "
145 "(target_tol) will not be synced when the latter changes and "
146 "`solver.run()` is called.")
148 .add_property("linesearch",
149 bp::make_function(
150 +[](const SolverType &s) -> const ls_variant_t & {
151 return s.linesearch_;
152 },
153 eigenpy::ReturnInternalVariant<ls_variant_t>{}))
154 .def("run", &SolverType::run,
155 ("self"_a, "problem", "xs_init"_a = bp::list(),
156 "us_init"_a = bp::list(), "vs_init"_a = bp::list(),
157 "lams_init"_a = bp::list()),
158 "Run the algorithm. Can receive initial guess for "
159 "multiplier trajectory.");
160
161 bp::class_<NonmonotoneLinesearch<Scalar>, bp::bases<Linesearch<Scalar>>>(
162 "NonmonotoneLinesearch", bp::no_init)
163 .def(bp::init<LsOptions>(("self"_a, "options")))
164 .def_readwrite("avg_eta", &NonmonotoneLinesearch<Scalar>::avg_eta)
165 .def_readwrite("beta_dec", &NonmonotoneLinesearch<Scalar>::beta_dec);
166
167 {
168 using AlmParams = SolverType::AlmParams;
169 bp::scope scope{cls};
170#define _c(name) def_readwrite(#name, &AlmParams::name)
171 bp::class_<AlmParams>("AlmParams", "Parameters for the ALM algorithm",
172 bp::init<>("self"_a))
173 ._c(prim_alpha)
174 ._c(prim_beta)
175 ._c(dual_alpha)
176 ._c(dual_beta)
177 ._c(mu_update_factor)
178 ._c(dyn_al_scale)
179 ._c(mu_lower_bound);
180#undef _c
181 }
182}
183
184} // namespace python
185} // namespace aligator
Main package namespace.
StepAcceptanceStrategy
Whether to use linesearch or filter during step acceptance phase.
Definition enums.hpp:29
HessianApprox
Definition enums.hpp:14
@ GAUSS_NEWTON
Use the Gauss-Newton approximation.
Definitions for the proximal trajectory optimization algorithm.
Nonmonotone Linesearch algorithm. Modifies the Armijo condition with a moving average of function val...
A proximal, augmented Lagrangian-type solver for trajectory optimization.
Trajectory optimization problem.
Definition fwd.hpp:104
Workspace for solver SolverProxDDP.
Definition workspace.hpp:28