aligator  0.9.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
12
13#include "workspace.hpp"
14#include "results.hpp"
15
16#include <boost/unordered_map.hpp>
17
18namespace aligator {
19namespace gar {
20template <typename Scalar> class RiccatiSolverBase;
21} // namespace gar
22
24
33template <typename _Scalar> struct SolverProxDDPTpl {
34public:
35 // typedefs
36
37 using Scalar = _Scalar;
47 using CallbackPtr = shared_ptr<CallbackBaseTpl<Scalar>>;
48 using CallbackMap = boost::unordered_map<std::string, CallbackPtr>;
52 using LinesearchOptions = typename Linesearch<Scalar>::Options;
53 using LinesearchType = proxsuite::nlp::ArmijoLinesearch<Scalar>;
55
56 struct AlmParams {
70 Scalar mu_lower_bound = 1e-8; //< Minimum possible penalty parameter.
71 };
72
81
82private:
85 Scalar target_dual_tol_;
88 bool sync_dual_tol;
89
90public:
91 Scalar mu_init = 0.01; //< Initial AL parameter
92
94
95 Scalar reg_min = 1e-10; //< Minimal nonzero regularization
96 Scalar reg_max = 1e9; //< Maximum regularization value
97 Scalar reg_init = 1e-9; //< Initial regularization value (can be zero)
98 Scalar reg_inc_k_ = 10.; //< Regularization increase factor
99 Scalar reg_inc_first_k_ = 100.; //< Regularization increase (critical)
100 Scalar reg_dec_k_ = 1. / 3.; //< Regularization decrease factor
101 Scalar preg_ = reg_init; //< Primal regularization value
102 Scalar preg_last_ = 0.; //< Last "good" regularization value
103
105
108
111
113 VerboseLevel verbose_;
116 bool lq_print_detailed = false;
122 LinesearchStrategy ls_strat = LinesearchStrategy::ARMIJO;
135
139
141 0; //< Max number of KKT system refinement iters
142 Scalar refinement_threshold_ = 1e-13; //< Target tol. for the KKT system.
143 std::size_t max_iters; //< Max number of Newton iterations.
144 std::size_t max_al_iters = 100; //< Maximum number of ALM iterations.
145 uint rollout_max_iters; //< Nonlinear rollout options
146
150 std::unique_ptr<gar::RiccatiSolverBase<Scalar>> linearSolver_;
154
155private:
157 CallbackMap callbacks_;
159 std::size_t num_threads_ = 1;
163 Scalar mu_penal_ = mu_init;
164 Scalar mu_penal_inv_ = 1. / mu_penal_;
165
166public:
167 SolverProxDDPTpl(const Scalar tol = 1e-6, const Scalar mu_init = 0.01,
168 const std::size_t max_iters = 1000,
169 VerboseLevel verbose = VerboseLevel::QUIET,
171
172 inline std::size_t getNumThreads() const { return num_threads_; }
173 void setNumThreads(const std::size_t num_threads);
174
175 Scalar getDualTolerance() const { return target_dual_tol_; }
177 void setDualTolerance(const Scalar tol) {
178 target_dual_tol_ = tol;
179 sync_dual_tol = false;
180 }
181
187 Scalar tryLinearStep(const Problem &problem, const Scalar alpha);
188
193 Scalar tryNonlinearRollout(const Problem &problem, const Scalar alpha);
194
195 Scalar forwardPass(const Problem &problem, const Scalar alpha);
196
198
203 void setup(const Problem &problem);
204 void cycleProblem(const Problem &problem,
205 shared_ptr<StageDataTpl<Scalar>> data);
206
215 bool run(const Problem &problem, const std::vector<VectorXs> &xs_init = {},
216 const std::vector<VectorXs> &us_init = {},
217 const std::vector<VectorXs> &vs_init = {},
218 const std::vector<VectorXs> &lams_init = {});
219
222 bool innerLoop(const Problem &problem);
223
228 void computeInfeasibilities(const Problem &problem);
231
234
236 void registerCallback(const std::string &name, CallbackPtr cb);
237
239 void clearCallbacks() noexcept { callbacks_.clear(); }
240
241 const CallbackMap &getCallbacks() const { return callbacks_; }
242 void removeCallback(const std::string &name) { callbacks_.erase(name); }
243 auto getCallbackNames() const {
244 std::vector<std::string> keys;
245 for (const auto &item : callbacks_) {
246 keys.push_back(item.first);
247 }
248 return keys;
249 }
250
251 CallbackPtr getCallback(const std::string &name) const {
252 auto cb = callbacks_.find(name);
253 if (cb != end(callbacks_)) {
254 return cb->second;
255 }
256 return nullptr;
257 }
258
260 void invokeCallbacks(Workspace &workspace, Results &results) {
261 for (const auto &cb : callbacks_) {
262 cb.second->call(workspace, results);
263 }
264 }
266
271 bool computeMultipliers(const Problem &problem,
272 const std::vector<VectorXs> &lams,
273 const std::vector<VectorXs> &vs);
274
276 return bcl_params.dyn_al_scale * mu_penal_;
277 }
278 ALIGATOR_INLINE Scalar mu() const { return mu_penal_; }
279 ALIGATOR_INLINE Scalar mu_inv() const { return mu_penal_inv_; }
280
283 inline void updateGains();
284
285protected:
286 void updateTolsOnFailure() noexcept {
287 const Scalar arg = std::min(mu_penal_, 0.99);
288 prim_tol_ = prim_tol0 * std::pow(arg, bcl_params.prim_alpha);
289 inner_tol_ = inner_tol0 * std::pow(arg, bcl_params.dual_alpha);
290 }
291
292 void updateTolsOnSuccess() noexcept {
293 const Scalar arg = std::min(mu_penal_, 0.99);
294 prim_tol_ = prim_tol_ * std::pow(arg, bcl_params.prim_beta);
295 inner_tol_ = inner_tol_ * std::pow(arg, bcl_params.dual_beta);
296 }
297
299 ALIGATOR_INLINE void setAlmPenalty(Scalar new_mu) noexcept {
300 mu_penal_ = std::max(new_mu, bcl_params.mu_lower_bound);
301 mu_penal_inv_ = 1. / mu_penal_;
302 }
303
304 // See sec. 3.1 of the IPOPT paper [Wächter, Biegler 2006]
305 // called before first bwd pass attempt
306 inline void initializeRegularization() noexcept {
307 if (preg_last_ == 0.) {
308 // this is the 1st iteration
309 preg_ = std::max(reg_init, reg_min);
310 } else {
311 // attempt decrease from last "good" value
312 preg_ = std::max(reg_min, preg_last_ * reg_dec_k_);
313 }
314 }
315
316 inline void increaseRegularization() noexcept {
317 if (preg_last_ == 0.)
319 else
320 preg_ *= reg_inc_k_;
321 }
322};
323
324} // namespace aligator
325
326#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
327#include "solver-proxddp.txx"
328#endif
#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:41
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:104
Data struct for CostAbstractTpl.
Definition fwd.hpp:68
A basic filter line-search strategy.
Definition fwd.hpp:131
A table logging utility to log the trace of the numerical solvers.
Definition logger.hpp:31
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.
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.
proxsuite::nlp::ArmijoLinesearch< Scalar > LinesearchType
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.
LinesearchStrategy ls_strat
Type of linesearch strategy. Default is Armijo.
SolverProxDDPTpl(const Scalar tol=1e-6, const Scalar mu_init=0.01, const std::size_t max_iters=1000, VerboseLevel verbose=VerboseLevel::QUIET, HessianApprox hess_approx=HessianApprox::GAUSS_NEWTON)
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
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
LinesearchType linesearch_
Linesearch function.
LinesearchMode ls_mode
Linesearch mode.
ALIGATOR_INLINE Scalar mu_inv() const
ALIGATOR_INLINE void setAlmPenalty(Scalar new_mu) noexcept
Set dual proximal/ALM penalty parameter.
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
StepAcceptanceStrategy sa_strategy
Step acceptance mode.
Data struct for stage models StageModelTpl.
Definition fwd.hpp:96
Base struct for function data.
Definition fwd.hpp:62
A stage in the control problem.
Definition fwd.hpp:93
Problem data struct.
Definition fwd.hpp:110
Trajectory optimization problem.
Definition fwd.hpp:107
Workspace for solver SolverProxDDP.
Definition workspace.hpp:28