aligator  0.10.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
solver-proxddp.hpp
Go to the documentation of this file.
1
4#pragma once
5
14
15#include "workspace.hpp"
16#include "results.hpp"
17
18#include <boost/unordered_map.hpp>
19#include <variant>
20
21namespace aligator {
22namespace gar {
23template <typename Scalar> class RiccatiSolverBase;
24} // namespace gar
25
27
36template <typename _Scalar> struct SolverProxDDPTpl {
37public:
38 using Scalar = _Scalar;
48 using CallbackPtr = shared_ptr<CallbackBaseTpl<Scalar>>;
49 using CallbackMap = boost::unordered_map<std::string, CallbackPtr>;
53 using LinesearchOptions = typename Linesearch<Scalar>::Options;
54
56 using fun_t = std::function<Scalar(Scalar)>;
57 using variant_t = std::variant<std::monostate, ArmijoLinesearch<Scalar>,
59
60 Scalar run(const fun_t &fun, const Scalar phi0, const Scalar dphi0,
61 Scalar &alpha_try) {
62 return std::visit(
63 overloads{[](std::monostate &) {
64 return std::numeric_limits<Scalar>::quiet_NaN();
65 },
66 [&](auto &&method) {
67 return method.run(fun, phi0, dphi0, alpha_try);
68 }},
69 impl_);
70 }
71
72 void reset() {
73 std::visit(overloads{[](std::monostate &) {},
74 [&](auto &&method) { method.reset(); }},
75 impl_);
76 }
77
78 Scalar isValid() const { return impl_.index() > 0ul; }
79
80 operator const variant_t &() const { return impl_; }
81
82 private:
83 explicit LinesearchVariant() {}
84 void init(StepAcceptanceStrategy strat, const LinesearchOptions &options) {
85 switch (strat) {
87 impl_ = ArmijoLinesearch<Scalar>(options);
88 break;
90 impl_ = NonmonotoneLinesearch<Scalar>(options);
91 break;
92 default:
93 ALIGATOR_WARNING("LinesearchVariant::",
94 "provided StepAcceptanceStrategy is invalid.");
95 break;
96 }
97 }
98 friend SolverProxDDPTpl;
99 variant_t impl_;
100 };
101
102 struct AlmParams {
116 Scalar mu_lower_bound = 1e-8; //< Minimum possible penalty parameter.
117 };
118
127
128private:
131 Scalar target_dual_tol_;
134 bool sync_dual_tol;
135
136public:
137 Scalar mu_init = 0.01; //< Initial AL parameter
138
140
141 Scalar reg_min = 1e-10; //< Minimal nonzero regularization
142 Scalar reg_max = 1e9; //< Maximum regularization value
143 Scalar reg_init = 1e-9; //< Initial regularization value (can be zero)
144 Scalar reg_inc_k_ = 10.; //< Regularization increase factor
145 Scalar reg_inc_first_k_ = 100.; //< Regularization increase (critical)
146 Scalar reg_dec_k_ = 1. / 3.; //< Regularization decrease factor
147 Scalar preg_ = reg_init; //< Primal regularization value
148 Scalar preg_last_ = 0.; //< Last "good" regularization value
149
151
154
157
159 VerboseLevel verbose_;
178
182
184 0; //< Max number of KKT system refinement iters
185 Scalar refinement_threshold_ = 1e-13; //< Target tol. for the KKT system.
186 std::size_t max_iters; //< Max number of Newton iterations.
187 std::size_t max_al_iters = 100; //< Maximum number of ALM iterations.
188 uint rollout_max_iters; //< Nonlinear rollout options
189
193 std::unique_ptr<gar::RiccatiSolverBase<Scalar>> linearSolver_;
197
198private:
200 CallbackMap callbacks_;
202 std::size_t num_threads_ = 1;
206 Scalar mu_penal_ = mu_init;
207 Scalar mu_penal_inv_ = 1. / mu_penal_;
208
209public:
210 SolverProxDDPTpl(const Scalar tol = 1e-6, const Scalar mu_init = 0.01,
211 const std::size_t max_iters = 1000,
212 VerboseLevel verbose = VerboseLevel::QUIET,
213 StepAcceptanceStrategy sa_strategy =
216
217 inline std::size_t getNumThreads() const { return num_threads_; }
218 void setNumThreads(const std::size_t num_threads);
219
220 Scalar getDualTolerance() const { return target_dual_tol_; }
222 void setDualTolerance(const Scalar tol) {
223 target_dual_tol_ = tol;
224 sync_dual_tol = false;
225 }
226
232 Scalar tryLinearStep(const Problem &problem, const Scalar alpha);
233
238 Scalar tryNonlinearRollout(const Problem &problem, const Scalar alpha);
239
240 Scalar forwardPass(const Problem &problem, const Scalar alpha);
241
243
248 void setup(const Problem &problem);
249 void cycleProblem(const Problem &problem,
250 shared_ptr<StageDataTpl<Scalar>> data);
251
260 bool run(const Problem &problem, const std::vector<VectorXs> &xs_init = {},
261 const std::vector<VectorXs> &us_init = {},
262 const std::vector<VectorXs> &vs_init = {},
263 const std::vector<VectorXs> &lams_init = {});
264
267 bool innerLoop(const Problem &problem);
268
273 void computeInfeasibilities(const Problem &problem);
276
279
281 void registerCallback(const std::string &name, CallbackPtr cb);
282
284 void clearCallbacks() noexcept { callbacks_.clear(); }
285
286 const CallbackMap &getCallbacks() const { return callbacks_; }
287 void removeCallback(const std::string &name) { callbacks_.erase(name); }
288 auto getCallbackNames() const {
289 std::vector<std::string> keys;
290 for (const auto &item : callbacks_) {
291 keys.push_back(item.first);
292 }
293 return keys;
294 }
295
296 CallbackPtr getCallback(const std::string &name) const {
297 auto cb = callbacks_.find(name);
298 if (cb != end(callbacks_)) {
299 return cb->second;
300 }
301 return nullptr;
302 }
303
305 void invokeCallbacks(Workspace &workspace, Results &results) {
306 for (const auto &cb : callbacks_) {
307 cb.second->call(workspace, results);
308 }
309 }
311
316 bool computeMultipliers(const Problem &problem,
317 const std::vector<VectorXs> &lams,
318 const std::vector<VectorXs> &vs);
319
321 return bcl_params.dyn_al_scale * mu_penal_;
322 }
323 ALIGATOR_INLINE Scalar mu() const { return mu_penal_; }
324 ALIGATOR_INLINE Scalar mu_inv() const { return mu_penal_inv_; }
325
328 inline void updateGains();
329
330protected:
331 void updateTolsOnFailure() noexcept {
332 const Scalar arg = std::min(mu_penal_, 0.99);
333 prim_tol_ = prim_tol0 * std::pow(arg, bcl_params.prim_alpha);
334 inner_tol_ = inner_tol0 * std::pow(arg, bcl_params.dual_alpha);
335 }
336
337 void updateTolsOnSuccess() noexcept {
338 const Scalar arg = std::min(mu_penal_, 0.99);
339 prim_tol_ = prim_tol_ * std::pow(arg, bcl_params.prim_beta);
340 inner_tol_ = inner_tol_ * std::pow(arg, bcl_params.dual_beta);
341 }
342
344 ALIGATOR_INLINE void setAlmPenalty(Scalar new_mu) noexcept {
345 mu_penal_ = std::max(new_mu, bcl_params.mu_lower_bound);
346 mu_penal_inv_ = 1. / mu_penal_;
347 }
348
349 // See sec. 3.1 of the IPOPT paper [Wächter, Biegler 2006]
350 // called before first bwd pass attempt
351 inline void initializeRegularization() noexcept {
352 if (preg_last_ == 0.) {
353 // this is the 1st iteration
354 preg_ = std::max(reg_init, reg_min);
355 } else {
356 // attempt decrease from last "good" value
357 preg_ = std::max(reg_min, preg_last_ * reg_dec_k_);
358 }
359 }
360
361 inline void increaseRegularization() noexcept {
362 if (preg_last_ == 0.)
364 else
365 preg_ *= reg_inc_k_;
366 }
367};
368
369} // namespace aligator
370
371#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
372#include "solver-proxddp.txx"
373#endif
#define ALIGATOR_WARNING(loc,...)
#define ALIGATOR_INLINE
Definition macros.hpp:13
Main package namespace.
MultiplierUpdateMode
Definition enums.hpp:23
StepAcceptanceStrategy
Whether to use linesearch or filter during step acceptance phase.
Definition enums.hpp:29
RolloutType
Definition enums.hpp:5
@ NONLINEAR
Nonlinear rollout, using the full dynamics.
unsigned int uint
Definition logger.hpp:10
HessianApprox
Definition enums.hpp:14
@ GAUSS_NEWTON
Use the Gauss-Newton approximation.
proxsuite::nlp::ConstraintSetBase< T > ConstraintSetTpl
TYPEDEFS FROM PROXNLP.
Definition fwd.hpp:38
LinesearchMode
Whether to use merit functions in primal or primal-dual mode.
Definition enums.hpp:26
Define workspace for the ProxDDP solver.
Convenience class to manage a stack of constraints.
Definition fwd.hpp:101
Data struct for CostAbstractTpl.
Definition fwd.hpp:65
A basic filter line-search strategy.
Definition fwd.hpp:128
A table logging utility to log the trace of the numerical solvers.
Definition logger.hpp:31
Nonmonotone Linesearch algorithm. Modifies the Armijo condition with a moving average of function val...
Scalar mu_update_factor
Scale factor for the dual proximal penalty.
Scalar dual_beta
Log-factor for dual tolerance (success)
Scalar dual_alpha
Log-factor for dual tolerance (failure)
Scalar dyn_al_scale
Constraints AL scaling.
Scalar prim_beta
Log-factor for primal tolerance (success)
Scalar prim_alpha
Log-factor for primal tolerance (failure)
Scalar mu_lower_bound
Lower bound on AL parameter.
Scalar run(const fun_t &fun, const Scalar phi0, const Scalar dphi0, Scalar &alpha_try)
std::variant< std::monostate, ArmijoLinesearch< Scalar >, NonmonotoneLinesearch< Scalar > > variant_t
A proximal, augmented Lagrangian-type solver for trajectory optimization.
Scalar tryLinearStep(const Problem &problem, const Scalar alpha)
Try a step of size .
CallbackPtr getCallback(const std::string &name) const
MultiplierUpdateMode multiplier_update_mode
Type of Lagrange multiplier update.
void updateGains()
Update primal-dual feedback gains (control, costate, path multiplier)
void computeCriterion()
Compute stationarity criterion (dual infeasibility).
void removeCallback(const std::string &name)
Scalar prim_tol_
Desired primal feasibility (for each outer loop)
bool run(const Problem &problem, const std::vector< VectorXs > &xs_init={}, const std::vector< VectorXs > &us_init={}, const std::vector< VectorXs > &vs_init={}, const std::vector< VectorXs > &lams_init={})
Run the numerical solver.
std::size_t getNumThreads() const
bool computeMultipliers(const Problem &problem, const std::vector< VectorXs > &lams, const std::vector< VectorXs > &vs)
ALIGATOR_INLINE Scalar mu() const
Scalar dual_weight
Weight of the dual variables in the primal-dual linesearch.
shared_ptr< CallbackBaseTpl< Scalar > > CallbackPtr
void invokeCallbacks(Workspace &workspace, Results &results)
Invoke callbacks.
ALIGATOR_INLINE Scalar mudyn() const
void clearCallbacks() noexcept
Remove all callbacks from the instance.
std::unique_ptr< gar::RiccatiSolverBase< Scalar > > linearSolver_
LQR subproblem solver.
boost::unordered_map< std::string, CallbackPtr > CallbackMap
LinesearchVariant linesearch_
Linesearch function.
LQSolverChoice linear_solver_choice
Choice of linear solver.
Scalar forwardPass(const Problem &problem, const Scalar alpha)
ConstraintSetTpl< Scalar > CstrSet
void cycleProblem(const Problem &problem, shared_ptr< StageDataTpl< Scalar > > data)
RolloutType rollout_type_
Type of rollout for the forward pass.
LinesearchOptions ls_params
Linesearch options, as in proxsuite-nlp.
void setup(const Problem &problem)
Allocate new workspace and results instances according to the specifications of problem.
Scalar inner_tol_
Subproblem tolerance.
HessianApprox hess_approx_
Type of Hessian approximation. Default is Gauss-Newton.
const CallbackMap & getCallbacks() const
void setNumThreads(const std::size_t num_threads)
void initializeRegularization() noexcept
void updateTolsOnSuccess() noexcept
LinesearchMode ls_mode
Linesearch mode.
SolverProxDDPTpl(const Scalar tol=1e-6, const Scalar mu_init=0.01, const std::size_t max_iters=1000, VerboseLevel verbose=VerboseLevel::QUIET, StepAcceptanceStrategy sa_strategy=StepAcceptanceStrategy::LINESEARCH_NONMONOTONE, HessianApprox hess_approx=HessianApprox::GAUSS_NEWTON)
ALIGATOR_INLINE Scalar mu_inv() const
ALIGATOR_INLINE void setAlmPenalty(Scalar new_mu) noexcept
Set dual proximal/ALM penalty parameter.
StepAcceptanceStrategy sa_strategy_
Step acceptance mode.
FilterTpl< Scalar > filter_
bool innerLoop(const Problem &problem)
Perform the inner loop of the algorithm (augmented Lagrangian minimization).
void increaseRegularization() noexcept
VerboseLevel verbose_
Solver verbosity level.
void registerCallback(const std::string &name, CallbackPtr cb)
Add a callback to the solver instance.
AlmParams bcl_params
Parameters for the BCL outer loop of the augmented Lagrangian algorithm.
Scalar tryNonlinearRollout(const Problem &problem, const Scalar alpha)
Policy rollout using the full nonlinear dynamics. The feedback gains need to be computed first....
void updateTolsOnFailure() noexcept
void setDualTolerance(const Scalar tol)
Manually set desired dual feasibility tolerance.
void computeInfeasibilities(const Problem &problem)
Compute the primal infeasibility measures.
typename Linesearch< Scalar >::Options LinesearchOptions
Data struct for stage models StageModelTpl.
Definition fwd.hpp:93
Base struct for function data.
Definition fwd.hpp:59
A stage in the control problem.
Definition fwd.hpp:90
Problem data struct.
Definition fwd.hpp:107
Trajectory optimization problem.
Definition fwd.hpp:104
Workspace for solver SolverProxDDP.
Definition workspace.hpp:28
Utility helper struct for creating visitors from lambdas.
Definition overloads.hpp:6