16#include <boost/unordered_map.hpp>
48 using CallbackMap = boost::unordered_map<std::string, CallbackPtr>;
122 LinesearchStrategy
ls_strat = LinesearchStrategy::ARMIJO;
159 std::size_t num_threads_ = 1;
164 Scalar mu_penal_inv_ = 1. / mu_penal_;
169 VerboseLevel verbose = VerboseLevel::QUIET,
178 target_dual_tol_ = tol;
179 sync_dual_tol =
false;
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 = {});
244 std::vector<std::string> keys;
245 for (
const auto &item : callbacks_) {
246 keys.push_back(item.first);
252 auto cb = callbacks_.find(name);
253 if (cb != end(callbacks_)) {
261 for (
const auto &cb : callbacks_) {
262 cb.second->call(workspace, results);
272 const std::vector<VectorXs> &lams,
273 const std::vector<VectorXs> &vs);
287 const Scalar arg = std::min(mu_penal_, 0.99);
293 const Scalar arg = std::min(mu_penal_, 0.99);
301 mu_penal_inv_ = 1. / mu_penal_;
326#ifdef ALIGATOR_ENABLE_TEMPLATE_INSTANTIATION
327#include "solver-proxddp.txx"
StepAcceptanceStrategy
Whether to use linesearch or filter during step acceptance phase.
@ NONLINEAR
Nonlinear rollout, using the full dynamics.
@ GAUSS_NEWTON
Use the Gauss-Newton approximation.
proxsuite::nlp::ConstraintSetBase< T > ConstraintSetTpl
TYPEDEFS FROM PROXNLP.
LinesearchMode
Whether to use merit functions in primal or primal-dual mode.
Define workspace for the ProxDDP solver.
Convenience class to manage a stack of constraints.
Data struct for CostAbstractTpl.
A basic filter line-search strategy.
A table logging utility to log the trace of the numerical solvers.
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 refinement_threshold_
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)
auto getCallbackNames() const
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
bool force_initial_condition_
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)
ALIGATOR_DYNAMIC_TYPEDEFS(Scalar)
void initializeRegularization() noexcept
void updateTolsOnSuccess() noexcept
LinesearchType linesearch_
Linesearch function.
LinesearchMode ls_mode
Linesearch mode.
Scalar getDualTolerance() const
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
std::size_t max_refinement_steps_
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
void updateLQSubproblem()
StepAcceptanceStrategy sa_strategy
Step acceptance mode.
Data struct for stage models StageModelTpl.
Base struct for function data.
A stage in the control problem.
Trajectory optimization problem.
Workspace for solver SolverProxDDP.