aligator  0.16.0
A versatile and efficient C++ library for real-time constrained trajectory optimization.
Loading...
Searching...
No Matches
solver-proxddp.hpp
Go to the documentation of this file.
1
4#pragma once
5
16
17#include "workspace.hpp"
18#include "results.hpp"
19
20#include <boost/unordered_map.hpp>
21#include <variant>
22
23namespace aligator {
24
26
35template <typename _Scalar> struct SolverProxDDPTpl {
36public:
37 using Scalar = _Scalar;
46 using CallbackPtr = shared_ptr<CallbackBaseTpl<Scalar>>;
47 // boost::unordered_map support heterogeneous lookup (whereas std:: doesn't
48 // until C++20). we just need to provide the right extended hash function and
49 // transparent comparison op
50 using CallbackMap = boost::unordered_map<std::string, CallbackPtr,
51 ExtendedStringHash, std::equal_to<>>;
55 using LinearSolverPtr = std::unique_ptr<gar::RiccatiSolverBase<Scalar>>;
56
57 struct LinesearchVariant {
58 using VariantType = std::variant<std::monostate, ArmijoLinesearch<Scalar>,
60
61 Scalar run(const std::function<Scalar(Scalar)> &fun, const Scalar phi0,
62 const Scalar dphi0, Scalar &alpha_try) {
63 return std::visit(
64 overloads{[](std::monostate &) {
65 return std::numeric_limits<Scalar>::quiet_NaN();
66 },
67 [&](auto &method) {
68 return method.run(fun, phi0, dphi0, alpha_try);
69 }},
70 impl_);
71 }
72
73 void reset() {
74 std::visit(overloads{[](std::monostate &) {},
75 [&](auto &method) { method.reset(); }},
76 impl_);
77 }
78
79 [[nodiscard]] bool isValid() const { return impl_.index() > 0ul; }
80
81 operator const VariantType &() const { return impl_; }
82
83 private:
84 explicit LinesearchVariant() {}
85 void init(StepAcceptanceStrategy strat,
86 const LinesearchOptions<Scalar> &options) {
87 switch (strat) {
89 impl_ = ArmijoLinesearch(options);
90 break;
92 impl_ = NonmonotoneLinesearch(options);
93 break;
94 default:
96 "Provided StepAcceptanceStrategy value is invalid.");
97 break;
98 }
99 }
100 friend SolverProxDDPTpl;
101 VariantType impl_;
102 };
103
118
127 Scalar mu_init_; //< Initial AL parameter
128
131
132 Scalar reg_min = 1e-10; //< Minimal nonzero regularization
133 Scalar reg_max = 1e9; //< Maximum regularization value
134 Scalar reg_init = 1e-9; //< Initial regularization value (can be zero)
135 Scalar reg_inc_k_ = 10.; //< Regularization increase factor
136 Scalar reg_inc_first_k_ = 100.; //< Regularization increase (critical)
137 Scalar reg_dec_k_ = 1. / 3.; //< Regularization decrease factor
138 Scalar preg_ = reg_init; //< Primal regularization value
139 Scalar preg_last_ = 0.; //< Last "good" regularization value
140
142
143 Scalar inner_tol0 = 1.; //< Initial BCL inner subproblem tolerance
144 Scalar prim_tol0 = 1.; //< Initial BCL constraint infeasibility tolerance
145
148
166 AlmParams bcl_params;
169
170 bool force_initial_condition_ = true; //< Force initial condition @f$ x_0 @f$.
171 size_t max_refinement_steps_ = 0; //< Max KKT system refinement iters.
172 Scalar refinement_threshold_ = 1e-13; //< Target tol. for the KKT system.
173 size_t max_iters; //< Max number of Newton iterations.
174 size_t max_al_iters = 100; //< Maximum number of ALM iterations.
175
178 Workspace workspace_; //< Solver workspace
179 Results results_; //< Solver results
180 LinearSolverPtr linear_solver_; //< LQR subproblem solver
181 FilterTpl<Scalar> filter_; //< Filter linesearch
182 LinesearchVariant linesearch_; //< Linesearch routine
183
184public:
185 SolverProxDDPTpl(const Scalar tol = 1e-6, const Scalar mu_init = 0.01,
186 const size_t max_iters = 1000,
188 StepAcceptanceStrategy sa_strategy =
191
192 [[nodiscard]] inline size_t getNumThreads() const { return num_threads_; }
193 void setNumThreads(const size_t num_threads);
194
195 [[nodiscard]] Scalar getDualTolerance() const { return target_dual_tol_; }
197 void setDualTolerance(const Scalar tol) {
198 target_dual_tol_ = tol;
199 sync_dual_tol_ = false;
200 }
201
207 Scalar tryLinearStep(const Problem &problem, const Scalar alpha);
208
213 Scalar tryNonlinearRollout(const Problem &problem, const Scalar alpha);
214
215 Scalar forwardPass(const Problem &problem, const Scalar alpha);
216
218
223 void setup(const Problem &problem);
224 void cycleProblem(const Problem &problem, const shared_ptr<StageData> &data);
225
234 bool run(const Problem &problem, const std::vector<VectorXs> &xs_init = {},
235 const std::vector<VectorXs> &us_init = {},
236 const std::vector<VectorXs> &vs_init = {},
237 const std::vector<VectorXs> &lams_init = {});
238
241 bool innerLoop(const Problem &problem);
242
245
248
250 void registerCallback(std::string_view name, CallbackPtr cb) {
251 callbacks_.insert_or_assign(name, cb);
252 }
253
255 void clearCallbacks() noexcept { callbacks_.clear(); }
256
257 const CallbackMap &getCallbacks() const { return callbacks_; }
258
259 [[nodiscard]] bool removeCallback(std::string_view name) {
260 return callbacks_.erase(name);
261 }
262
263 [[nodiscard]] auto getCallbackNames() const {
264 std::vector<std::string_view> keys;
265 for (const auto &item : callbacks_) {
266 keys.push_back(item.first);
267 }
268 return keys;
269 }
270
271 [[nodiscard]] CallbackPtr getCallback(std::string_view name) const {
272 auto cb = callbacks_.find(name);
273 if (cb != end(callbacks_)) {
274 return cb->second;
275 }
276 return nullptr;
277 }
278
281 for (const auto &cb : callbacks_) {
282 cb.second->call(workspace_, results_);
283 }
284 }
285
286
292 bool computeMultipliers(const Problem &problem,
293 const std::vector<VectorXs> &xs,
294 const std::vector<VectorXs> &lams,
295 const std::vector<VectorXs> &vs);
296
297 inline Scalar mu() const { return mu_penal_; }
298 inline Scalar mu_inv() const { return 1. / mu_penal_; }
300 inline Scalar mu_dyn() const { return 0.1 * mu_penal_; }
301
302protected:
303 Scalar target_dual_tol_; //< Solver desired dual feasibility (default: same as
304 // target_tol_)
305 bool sync_dual_tol_ = true; //< If true, dual tolerance will be set to
306 // target_tol_ when run() is called.
307 CallbackMap callbacks_; //< Solver callbacks
308 size_t num_threads_ = 1; //< Number of threads
312
313 void updateTolsOnFailure() noexcept {
314 const Scalar arg = std::min(mu_penal_, 0.99);
315 prim_tol_ = prim_tol0 * std::pow(arg, bcl_params.prim_alpha);
316 inner_tol_ = inner_tol0 * std::pow(arg, bcl_params.dual_alpha);
317 }
318
319 void updateTolsOnSuccess() noexcept {
320 const Scalar arg = std::min(mu_penal_, 0.99);
321 prim_tol_ = prim_tol_ * std::pow(arg, bcl_params.prim_beta);
322 inner_tol_ = inner_tol_ * std::pow(arg, bcl_params.dual_beta);
323 }
324
326 inline void setAlmPenalty(Scalar new_mu) noexcept {
327 mu_penal_ = std::max(new_mu, bcl_params.mu_lower_bound);
328 }
329
333 inline void initializeRegularization() noexcept {
334 if (preg_last_ == 0.) {
335 // this is the 1st iteration
336 preg_ = std::max(reg_init, reg_min);
337 } else {
338 // attempt decrease from last "good" value
339 preg_ = std::max(reg_min, preg_last_ * reg_dec_k_);
340 }
341 }
342
343 inline void increaseRegularization() noexcept {
344 if (preg_last_ == 0.)
346 else
347 preg_ *= reg_inc_k_;
348 }
349};
350
351#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
352extern template struct SolverProxDDPTpl<context::Scalar>;
353#endif
354} // namespace aligator
A memory_resource wrapping around mimalloc.
A convenience subclass of std::pmr::polymorphic_allocator for bytes.
Definition allocator.hpp:16
#define ALIGATOR_RUNTIME_ERROR(...)
Definition exceptions.hpp:7
Implements a basic Armijo back-tracking strategy.
Main package namespace.
MultiplierUpdateMode
Definition enums.hpp:23
VerboseLevel
Verbosity level.
Definition fwd.hpp:82
@ QUIET
Definition fwd.hpp:82
StepAcceptanceStrategy
Whether to use linesearch or filter during step acceptance phase.
Definition enums.hpp:29
RolloutType
Definition enums.hpp:5
@ LINEAR
Linear rollout.
Definition enums.hpp:7
NonmonotoneLinesearch(const LinesearchOptions< Scalar > &) -> NonmonotoneLinesearch< Scalar >
ArmijoLinesearch(const LinesearchOptions< Scalar > &) -> ArmijoLinesearch< Scalar >
HessianApprox
Definition enums.hpp:14
@ GAUSS_NEWTON
Use the Gauss-Newton approximation.
Definition enums.hpp:18
LinesearchMode
Whether to use merit functions in primal or primal-dual mode.
Definition enums.hpp:26
Define workspace for the ProxDDP solver.
Base constraint set type.
Convenience class to manage a stack of constraints.
Data struct for CostAbstractTpl.
Extended hashing function for strings which supports const char* and std::string_view.
A basic filter line-search strategy.
Definition filter.hpp:12
A table logging utility to log the trace of the numerical solvers.
Definition logger.hpp:32
Nonmonotone Linesearch algorithm. Modifies the Armijo condition with a moving average of function val...
Results holder struct.
Definition results.hpp:11
Scalar mu_update_factor
Scale factor for ALM parameter.
Scalar dual_beta
for dual tolerance (success)
Scalar dual_alpha
for dual tolerance (failure)
Scalar prim_beta
for primal tolerance (success)
Scalar prim_alpha
for primal tolerance (failure)
Scalar mu_lower_bound
Lower bound on AL parameter.
Scalar run(const std::function< Scalar(Scalar)> &fun, const Scalar phi0, const Scalar dphi0, Scalar &alpha_try)
std::variant< std::monostate, ArmijoLinesearch< Scalar >, NonmonotoneLinesearch< Scalar > > VariantType
Scalar tryLinearStep(const Problem &problem, const Scalar alpha)
Try a step of size .
void setAlmPenalty(Scalar new_mu) noexcept
Set dual proximal/ALM penalty parameter.
void computeCriterion()
Compute stationarity criterion (dual infeasibility).
Scalar mu_dyn() const
Used in linesearch.
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.
boost::unordered_map< std::string, CallbackPtr, ExtendedStringHash, std::equal_to<> > CallbackMap
shared_ptr< CallbackBaseTpl< Scalar > > CallbackPtr
TrajOptDataTpl< Scalar > TrajOptData
void invokeCallbacks()
Invoke callbacks.
LinesearchOptions< Scalar > ls_params
void clearCallbacks() noexcept
Remove all callbacks from the instance.
std::unique_ptr< gar::RiccatiSolverBase< Scalar > > LinearSolverPtr
SolverProxDDPTpl(const Scalar tol=1e-6, const Scalar mu_init=0.01, const size_t max_iters=1000, VerboseLevel verbose=VerboseLevel::QUIET, StepAcceptanceStrategy sa_strategy=StepAcceptanceStrategy::LINESEARCH_NONMONOTONE, HessianApprox hess_approx=HessianApprox::GAUSS_NEWTON)
Scalar forwardPass(const Problem &problem, const Scalar alpha)
ConstraintSetTpl< Scalar > CstrSet
ConstraintStackTpl< Scalar > ConstraintStack
bool computeMultipliers(const Problem &problem, const std::vector< VectorXs > &xs, const std::vector< VectorXs > &lams, const std::vector< VectorXs > &vs)
void setup(const Problem &problem)
Allocate new workspace and results instances according to the specifications of problem.
const CallbackMap & getCallbacks() const
void cycleProblem(const Problem &problem, const shared_ptr< StageData > &data)
void initializeRegularization() noexcept
void updateTolsOnSuccess() noexcept
TrajOptProblemTpl< Scalar > Problem
bool innerLoop(const Problem &problem)
Perform the inner loop of the algorithm (augmented Lagrangian minimization).
void increaseRegularization() noexcept
StageFunctionDataTpl< Scalar > StageFunctionData
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 registerCallback(std::string_view name, CallbackPtr cb)
Add a callback to the solver instance.
void setDualTolerance(const Scalar tol)
Manually set desired dual feasibility tolerance.
bool removeCallback(std::string_view name)
CostDataAbstractTpl< Scalar > CostData
void setNumThreads(const size_t num_threads)
CallbackPtr getCallback(std::string_view name) const
Data struct for stage models StageModelTpl.
Base struct for function data.
A stage in the control problem.
Problem data struct.
Trajectory optimization problem.
Workspace for solver SolverProxDDP.
Definition workspace.hpp:27
Utility helper struct for creating visitors from lambdas.
Definition overloads.hpp:6