aligator  0.6.1
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
solver-fddp.hpp
Go to the documentation of this file.
1
6#pragma once
7
11
12#include "./results.hpp"
13#include "./workspace.hpp"
14
16#include "aligator/threads.hpp"
17
18#include <fmt/ostream.h>
19#include <unordered_map>
20
22#define ALIGATOR_FDDP_WARNING(msg) ALIGATOR_WARNING("SolverFDDP", msg)
23
24namespace aligator {
25
31template <typename Scalar> struct SolverFDDPTpl {
33 using Problem = TrajOptProblemTpl<Scalar>;
34 using StageModel = StageModelTpl<Scalar>;
35 using StageData = StageDataTpl<Scalar>;
36 using ProblemData = TrajOptDataTpl<Scalar>;
37 using Results = ResultsFDDPTpl<Scalar>;
38 using Workspace = WorkspaceFDDPTpl<Scalar>;
39 using Manifold = ManifoldAbstractTpl<Scalar>;
40 using VParams = ValueFunctionTpl<Scalar>;
41 using QParams = QFunctionTpl<Scalar>;
42 using CostData = CostDataAbstractTpl<Scalar>;
43 using ExpModel = ExplicitDynamicsModelTpl<Scalar>;
44 using ExplicitDynamicsData = ExplicitDynamicsDataTpl<Scalar>;
45 using CallbackPtr = shared_ptr<CallbackBaseTpl<Scalar>>;
46 using CallbackMap = std::unordered_map<std::string, CallbackPtr>;
47
49
52 Scalar reg_init;
53 Scalar preg_ = reg_init;
54 Scalar reg_min_ = 1e-9;
55 Scalar reg_max_ = 1e9;
57 Scalar reg_dec_factor_ = 0.1;
59 Scalar reg_inc_factor_ = 10.;
61
62 Scalar th_grad_ = 1e-12;
63 Scalar th_step_dec_ = 0.5;
64 Scalar th_step_inc_ = 0.01;
65
66 typename Linesearch<Scalar>::Options ls_params;
67
68 VerboseLevel verbose_;
70 std::size_t max_iters;
75
77
78 void setNumThreads(const std::size_t num_threads) {
79 num_threads_ = num_threads;
80 omp::set_default_options(num_threads);
81 }
82 std::size_t getNumThreads() const { return num_threads_; }
83
84protected:
86 std::size_t num_threads_;
89
90public:
93
94 SolverFDDPTpl(const Scalar tol = 1e-6,
95 VerboseLevel verbose = VerboseLevel::QUIET,
96 const Scalar reg_init = 1e-9,
97 const std::size_t max_iters = 200);
98
100 ALIGATOR_DEPRECATED const Results &getResults() const { return results_; }
102 ALIGATOR_DEPRECATED const Workspace &getWorkspace() const {
103 return workspace_;
104 }
105
107 void setup(const Problem &problem);
108
119 static Scalar forwardPass(const Problem &problem, const Results &results,
120 Workspace &workspace, const Scalar alpha);
121
128 void updateExpectedImprovement(Workspace &workspace, Results &results) const;
129
136 void expectedImprovement(Workspace &workspace, Scalar &d1, Scalar &d2) const;
137
144 inline Scalar computeInfeasibility(const Problem &problem);
145
147 void backwardPass(const Problem &problem, Workspace &workspace) const;
148
152 ALIGATOR_INLINE void acceptGains(const Workspace &workspace,
153 Results &results) const {
154 assert(workspace.kktRhs.size() == results.gains_.size());
156 results.gains_ = workspace.kktRhs;
157 }
158
159 inline void increaseRegularization() {
161 preg_ = std::min(preg_, reg_max_);
162 }
163
164 inline void decreaseRegularization() {
166 preg_ = std::max(preg_, reg_min_);
167 }
168
170 inline Scalar computeCriterion(Workspace &workspace);
171
173 void registerCallback(const std::string &name, CallbackPtr cb) {
174 callbacks_[name] = cb;
175 }
176
177 const CallbackMap &getCallbacks() const { return callbacks_; }
178 void removeCallback(const std::string &name) { callbacks_.erase(name); }
179 auto getCallback(const std::string &name) -> CallbackPtr {
180 auto cb = callbacks_.find(name);
181 if (cb != end(callbacks_)) {
182 return cb->second;
183 }
184 return nullptr;
185 }
186
188 void clearCallbacks() { callbacks_.clear(); }
189
190 void invokeCallbacks(Workspace &workspace, Results &results) {
191 for (const auto &cb : callbacks_) {
192 cb.second->call(workspace, results);
193 }
194 }
195
196 bool run(const Problem &problem, const std::vector<VectorXs> &xs_init = {},
197 const std::vector<VectorXs> &us_init = {});
198
199 static const ExplicitDynamicsData &
200 stage_get_dynamics_data(const StageDataTpl<Scalar> &data) {
201 const DynamicsDataTpl<Scalar> &dd = *data.dynamics_data;
202 return static_cast<const ExplicitDynamicsData &>(dd);
203 }
204};
205
206} // namespace aligator
207
208#include "./solver-fddp.hxx"
209
210#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
211#include "./solver-fddp.txx"
212#endif
#define ALIGATOR_NOMALLOC_SCOPED
#define ALIGATOR_INLINE
Definition macros.hpp:13
void set_default_options(std::size_t, bool=true)
Definition threads.hpp:38
Main package namespace.
constexpr auto data(C &c) noexcept(noexcept(c.data())) -> decltype(c.data())
Definition data.hpp:18
A table logging utility to log the trace of the numerical solvers.
Definition logger.hpp:37
The feasible DDP (FDDP) algorithm, from Mastalli et al. (2020).
ExplicitDynamicsModelTpl< Scalar > ExpModel
void updateExpectedImprovement(Workspace &workspace, Results &results) const
Pre-compute parts of the directional derivatives – this is done before linesearch.
WorkspaceFDDPTpl< Scalar > Workspace
ALIGATOR_DEPRECATED const Results & getResults() const
Get the solver results.
void setup(const Problem &problem)
Allocate workspace and results structs.
TrajOptProblemTpl< Scalar > Problem
Scalar reg_inc_factor_
Regularization increase factor.
static Scalar forwardPass(const Problem &problem, const Results &results, Workspace &workspace, const Scalar alpha)
Perform a nonlinear rollout, keeping an infeasibility gap.
void expectedImprovement(Workspace &workspace, Scalar &d1, Scalar &d2) const
Finish computing the directional derivatives – this is done within linesearch.
Linesearch< Scalar >::Options ls_params
Scalar reg_dec_factor_
Regularization decrease factor.
ALIGATOR_DEPRECATED const Workspace & getWorkspace() const
Get a const reference to the solver's workspace.
void setNumThreads(const std::size_t num_threads)
std::unordered_map< std::string, CallbackPtr > CallbackMap
ResultsFDDPTpl< Scalar > Results
std::size_t max_iters
Maximum number of iterations for the solver.
shared_ptr< CallbackBaseTpl< Scalar > > CallbackPtr
std::size_t getNumThreads() const
ManifoldAbstractTpl< Scalar > Manifold
QFunctionTpl< Scalar > QParams
ValueFunctionTpl< Scalar > VParams
std::size_t num_threads_
Number of threads to use when evaluating the problem or its derivatives.
CallbackMap callbacks_
Callbacks.
SolverFDDPTpl(const Scalar tol=1e-6, VerboseLevel verbose=VerboseLevel::QUIET, const Scalar reg_init=1e-9, const std::size_t max_iters=200)