aligator
0.10.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
|
The feasible DDP (FDDP) algorithm, from Mastalli et al. (2020). More...
#include <aligator/solvers/fddp/solver-fddp.hpp>
Public Types | |
using | Problem = TrajOptProblemTpl<Scalar> |
using | StageModel = StageModelTpl<Scalar> |
using | StageData = StageDataTpl<Scalar> |
using | ProblemData = TrajOptDataTpl<Scalar> |
using | Results = ResultsFDDPTpl<Scalar> |
using | Workspace = WorkspaceFDDPTpl<Scalar> |
using | Manifold = ManifoldAbstractTpl<Scalar> |
using | VParams = ValueFunctionTpl<Scalar> |
using | QParams = QFunctionTpl<Scalar> |
using | CostData = CostDataAbstractTpl<Scalar> |
using | ExpModel = ExplicitDynamicsModelTpl<Scalar> |
using | ExplicitDynamicsData = ExplicitDynamicsDataTpl<Scalar> |
using | CallbackPtr = shared_ptr<CallbackBaseTpl<Scalar>> |
using | CallbackMap = boost::unordered_map<std::string, CallbackPtr> |
Public Member Functions | |
ALIGATOR_DYNAMIC_TYPEDEFS (Scalar) | |
void | setNumThreads (const std::size_t num_threads) |
std::size_t | getNumThreads () const |
SolverFDDPTpl (const Scalar tol=1e-6, VerboseLevel verbose=VerboseLevel::QUIET, const Scalar reg_init=1e-9, const std::size_t max_iters=200) | |
void | setup (const Problem &problem) |
Allocate workspace and results structs. | |
void | updateExpectedImprovement (Workspace &workspace, Results &results) const |
Pre-compute parts of the directional derivatives – this is done before linesearch. | |
void | expectedImprovement (Workspace &workspace, Scalar &d1, Scalar &d2) const |
Finish computing the directional derivatives – this is done within linesearch. | |
Static Public Member Functions | |
static Scalar | forwardPass (const Problem &problem, const Results &results, Workspace &workspace, const Scalar alpha) |
Perform a nonlinear rollout, keeping an infeasibility gap. | |
Public Attributes | |
Scalar | target_tol_ |
Scalar | th_grad_ = 1e-12 |
Scalar | th_step_dec_ = 0.5 |
Scalar | th_step_inc_ = 0.01 |
Linesearch< Scalar >::Options | ls_params |
VerboseLevel | verbose_ |
std::size_t | max_iters |
Maximum number of iterations for the solver. | |
bool | force_initial_condition_ |
Logger | logger {} |
Results | results_ |
Workspace | workspace_ |
Regularization parameters | |
Scalar | reg_init |
Scalar | preg_ = reg_init |
Scalar | reg_min_ = 1e-9 |
Scalar | reg_max_ = 1e9 |
Scalar | reg_dec_factor_ = 0.1 |
Regularization decrease factor. | |
Scalar | reg_inc_factor_ = 10. |
Regularization increase factor. | |
Protected Attributes | |
std::size_t | num_threads_ |
Number of threads to use when evaluating the problem or its derivatives. | |
CallbackMap | callbacks_ |
Callbacks. | |
The feasible DDP (FDDP) algorithm, from Mastalli et al. (2020).
The implementation very similar to Crocoddyl's SolverFDDP.
Definition at line 27 of file solver-fddp.hpp.
using aligator::SolverFDDPTpl< Scalar >::Problem = TrajOptProblemTpl<Scalar> |
Definition at line 29 of file solver-fddp.hpp.
using aligator::SolverFDDPTpl< Scalar >::StageModel = StageModelTpl<Scalar> |
Definition at line 30 of file solver-fddp.hpp.
using aligator::SolverFDDPTpl< Scalar >::StageData = StageDataTpl<Scalar> |
Definition at line 31 of file solver-fddp.hpp.
using aligator::SolverFDDPTpl< Scalar >::ProblemData = TrajOptDataTpl<Scalar> |
Definition at line 32 of file solver-fddp.hpp.
using aligator::SolverFDDPTpl< Scalar >::Results = ResultsFDDPTpl<Scalar> |
Definition at line 33 of file solver-fddp.hpp.
using aligator::SolverFDDPTpl< Scalar >::Workspace = WorkspaceFDDPTpl<Scalar> |
Definition at line 34 of file solver-fddp.hpp.
using aligator::SolverFDDPTpl< Scalar >::Manifold = ManifoldAbstractTpl<Scalar> |
Definition at line 35 of file solver-fddp.hpp.
using aligator::SolverFDDPTpl< Scalar >::VParams = ValueFunctionTpl<Scalar> |
Definition at line 36 of file solver-fddp.hpp.
using aligator::SolverFDDPTpl< Scalar >::QParams = QFunctionTpl<Scalar> |
Definition at line 37 of file solver-fddp.hpp.
using aligator::SolverFDDPTpl< Scalar >::CostData = CostDataAbstractTpl<Scalar> |
Definition at line 38 of file solver-fddp.hpp.
using aligator::SolverFDDPTpl< Scalar >::ExpModel = ExplicitDynamicsModelTpl<Scalar> |
Definition at line 39 of file solver-fddp.hpp.
using aligator::SolverFDDPTpl< Scalar >::ExplicitDynamicsData = ExplicitDynamicsDataTpl<Scalar> |
Definition at line 40 of file solver-fddp.hpp.
using aligator::SolverFDDPTpl< Scalar >::CallbackPtr = shared_ptr<CallbackBaseTpl<Scalar>> |
Definition at line 41 of file solver-fddp.hpp.
using aligator::SolverFDDPTpl< Scalar >::CallbackMap = boost::unordered_map<std::string, CallbackPtr> |
Definition at line 42 of file solver-fddp.hpp.
aligator::SolverFDDPTpl< Scalar >::SolverFDDPTpl | ( | const Scalar | tol = 1e-6, |
VerboseLevel | verbose = VerboseLevel::QUIET, | ||
const Scalar | reg_init = 1e-9, | ||
const std::size_t | max_iters = 200 ) |
aligator::SolverFDDPTpl< Scalar >::ALIGATOR_DYNAMIC_TYPEDEFS | ( | Scalar | ) |
|
inline |
Definition at line 74 of file solver-fddp.hpp.
|
inline |
Definition at line 78 of file solver-fddp.hpp.
void aligator::SolverFDDPTpl< Scalar >::setup | ( | const Problem & | problem | ) |
Allocate workspace and results structs.
|
static |
Perform a nonlinear rollout, keeping an infeasibility gap.
Perform a nonlinear rollout using the computed sensitivity gains from the backward pass, while keeping the dynamical feasibility gaps open proportionally to the step-size alpha
.
[in] | problem | |
[in] | results | |
[out] | workspace | |
[in] | alpha | step-size. |
void aligator::SolverFDDPTpl< Scalar >::updateExpectedImprovement | ( | Workspace & | workspace, |
Results & | results ) const |
Pre-compute parts of the directional derivatives – this is done before linesearch.
Inspired from Crocoddyl's own function, crocoddyl::SolverFDDP::updateExpectedImprovement
void aligator::SolverFDDPTpl< Scalar >::expectedImprovement | ( | Workspace & | workspace, |
Scalar & | d1, | ||
Scalar & | d2 ) const |
Finish computing the directional derivatives – this is done within linesearch.
Inspired from Crocoddyl's own function, crocoddyl::SolverFDDP::expectedImprovement
Scalar aligator::SolverFDDPTpl< Scalar >::target_tol_ |
Definition at line 44 of file solver-fddp.hpp.
Scalar aligator::SolverFDDPTpl< Scalar >::reg_init |
Definition at line 48 of file solver-fddp.hpp.
Scalar aligator::SolverFDDPTpl< Scalar >::preg_ = reg_init |
Definition at line 49 of file solver-fddp.hpp.
Scalar aligator::SolverFDDPTpl< Scalar >::reg_min_ = 1e-9 |
Definition at line 50 of file solver-fddp.hpp.
Scalar aligator::SolverFDDPTpl< Scalar >::reg_max_ = 1e9 |
Definition at line 51 of file solver-fddp.hpp.
Scalar aligator::SolverFDDPTpl< Scalar >::reg_dec_factor_ = 0.1 |
Regularization decrease factor.
Definition at line 53 of file solver-fddp.hpp.
Scalar aligator::SolverFDDPTpl< Scalar >::reg_inc_factor_ = 10. |
Regularization increase factor.
Definition at line 55 of file solver-fddp.hpp.
Scalar aligator::SolverFDDPTpl< Scalar >::th_grad_ = 1e-12 |
Definition at line 58 of file solver-fddp.hpp.
Scalar aligator::SolverFDDPTpl< Scalar >::th_step_dec_ = 0.5 |
Definition at line 59 of file solver-fddp.hpp.
Scalar aligator::SolverFDDPTpl< Scalar >::th_step_inc_ = 0.01 |
Definition at line 60 of file solver-fddp.hpp.
Linesearch<Scalar>::Options aligator::SolverFDDPTpl< Scalar >::ls_params |
Definition at line 62 of file solver-fddp.hpp.
VerboseLevel aligator::SolverFDDPTpl< Scalar >::verbose_ |
Definition at line 64 of file solver-fddp.hpp.
std::size_t aligator::SolverFDDPTpl< Scalar >::max_iters |
Maximum number of iterations for the solver.
Definition at line 66 of file solver-fddp.hpp.
bool aligator::SolverFDDPTpl< Scalar >::force_initial_condition_ |
Crocoddyl's FDDP implementation forces the initial state in linesearch to satisfy the initial condition. This flag switches that behaviour on or off.
Definition at line 70 of file solver-fddp.hpp.
Logger aligator::SolverFDDPTpl< Scalar >::logger {} |
Definition at line 72 of file solver-fddp.hpp.
|
protected |
Number of threads to use when evaluating the problem or its derivatives.
Definition at line 82 of file solver-fddp.hpp.
|
protected |
Callbacks.
Definition at line 84 of file solver-fddp.hpp.
Results aligator::SolverFDDPTpl< Scalar >::results_ |
Definition at line 87 of file solver-fddp.hpp.
Workspace aligator::SolverFDDPTpl< Scalar >::workspace_ |
Definition at line 88 of file solver-fddp.hpp.