aligator  0.9.0
A primal-dual augmented Lagrangian-type solver for nonlinear trajectory optimization.
Loading...
Searching...
No Matches
aligator::SolverProxDDPTpl< _Scalar > Struct Template Reference

A proximal, augmented Lagrangian-type solver for trajectory optimization. More...

#include <aligator/solvers/proxddp/solver-proxddp.hpp>

Collaboration diagram for aligator::SolverProxDDPTpl< _Scalar >:
[legend]

Classes

struct  AlmParams
 

Public Types

using Scalar = _Scalar
 
using Problem = TrajOptProblemTpl<Scalar>
 
using Workspace = WorkspaceTpl<Scalar>
 
using Results = ResultsTpl<Scalar>
 
using StageFunctionData = StageFunctionDataTpl<Scalar>
 
using DynamicsData = DynamicsDataTpl<Scalar>
 
using CostData = CostDataAbstractTpl<Scalar>
 
using StageModel = StageModelTpl<Scalar>
 
using StageData = StageDataTpl<Scalar>
 
using CallbackPtr = shared_ptr<CallbackBaseTpl<Scalar>>
 
using CallbackMap = boost::unordered_map<std::string, CallbackPtr>
 
using ConstraintStack = ConstraintStackTpl<Scalar>
 
using CstrSet = ConstraintSetTpl<Scalar>
 
using TrajOptData = TrajOptDataTpl<Scalar>
 
using LinesearchOptions = typename Linesearch<Scalar>::Options
 
using LinesearchType = proxsuite::nlp::ArmijoLinesearch<Scalar>
 
using Filter = FilterTpl<Scalar>
 

Public Member Functions

 ALIGATOR_DYNAMIC_TYPEDEFS (Scalar)
 
 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)
 
std::size_t getNumThreads () const
 
void setNumThreads (const std::size_t num_threads)
 
Scalar getDualTolerance () const
 
void setDualTolerance (const Scalar tol)
 Manually set desired dual feasibility tolerance.
 
Scalar tryLinearStep (const Problem &problem, const Scalar alpha)
 Try a step of size \(\alpha\).
 
Scalar tryNonlinearRollout (const Problem &problem, const Scalar alpha)
 Policy rollout using the full nonlinear dynamics. The feedback gains need to be computed first. This will evaluate all the terms in the problem into the problem data, similar to TrajOptProblemTpl::evaluate().
 
Scalar forwardPass (const Problem &problem, const Scalar alpha)
 
void updateLQSubproblem ()
 
void setup (const Problem &problem)
 Allocate new workspace and results instances according to the specifications of problem.
 
void cycleProblem (const Problem &problem, shared_ptr< StageDataTpl< Scalar > > data)
 
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.
 
bool innerLoop (const Problem &problem)
 Perform the inner loop of the algorithm (augmented Lagrangian minimization).
 
void computeInfeasibilities (const Problem &problem)
 Compute the primal infeasibility measures.
 
void computeCriterion ()
 Compute stationarity criterion (dual infeasibility).
 
bool computeMultipliers (const Problem &problem, const std::vector< VectorXs > &lams, const std::vector< VectorXs > &vs)
 
ALIGATOR_INLINE Scalar mudyn () const
 
ALIGATOR_INLINE Scalar mu () const
 
ALIGATOR_INLINE Scalar mu_inv () const
 
void updateGains ()
 Update primal-dual feedback gains (control, costate, path multiplier)
 
callbacks
void registerCallback (const std::string &name, CallbackPtr cb)
 Add a callback to the solver instance.
 
void clearCallbacks () noexcept
 Remove all callbacks from the instance.
 
const CallbackMapgetCallbacks () const
 
void removeCallback (const std::string &name)
 
auto getCallbackNames () const
 
CallbackPtr getCallback (const std::string &name) const
 
void invokeCallbacks (Workspace &workspace, Results &results)
 Invoke callbacks.
 

Public Attributes

Scalar inner_tol_
 Subproblem tolerance.
 
Scalar prim_tol_
 Desired primal feasibility (for each outer loop)
 
Scalar target_tol_ = 1e-6
 
Scalar mu_init = 0.01
 
Scalar reg_min = 1e-10
 
Scalar reg_max = 1e9
 
Scalar reg_init = 1e-9
 
Scalar reg_inc_k_ = 10.
 
Scalar reg_inc_first_k_ = 100.
 
Scalar reg_dec_k_ = 1. / 3.
 
Scalar preg_ = reg_init
 
Scalar preg_last_ = 0.
 
Scalar inner_tol0 = 1.
 
Scalar prim_tol0 = 1.
 
Logger logger {}
 Logger.
 
VerboseLevel verbose_
 Solver verbosity level.
 
LQSolverChoice linear_solver_choice = LQSolverChoice::SERIAL
 Choice of linear solver.
 
bool lq_print_detailed = false
 
HessianApprox hess_approx_ = HessianApprox::GAUSS_NEWTON
 Type of Hessian approximation. Default is Gauss-Newton.
 
LinesearchOptions ls_params
 Linesearch options, as in proxsuite-nlp.
 
LinesearchStrategy ls_strat = LinesearchStrategy::ARMIJO
 Type of linesearch strategy. Default is Armijo.
 
MultiplierUpdateMode multiplier_update_mode = MultiplierUpdateMode::NEWTON
 Type of Lagrange multiplier update.
 
LinesearchMode ls_mode = LinesearchMode::PRIMAL
 Linesearch mode.
 
Scalar dual_weight = 1.0
 Weight of the dual variables in the primal-dual linesearch.
 
RolloutType rollout_type_ = RolloutType::NONLINEAR
 Type of rollout for the forward pass.
 
AlmParams bcl_params
 Parameters for the BCL outer loop of the augmented Lagrangian algorithm.
 
StepAcceptanceStrategy sa_strategy = StepAcceptanceStrategy::LINESEARCH
 Step acceptance mode.
 
bool force_initial_condition_ = true
 
std::size_t max_refinement_steps_
 
Scalar refinement_threshold_ = 1e-13
 
std::size_t max_iters
 
std::size_t max_al_iters = 100
 
uint rollout_max_iters
 
Workspace workspace_
 
Results results_
 
std::unique_ptr< gar::RiccatiSolverBase< Scalar > > linearSolver_
 LQR subproblem solver.
 
Filter filter_
 
LinesearchType linesearch_
 Linesearch function.
 

Protected Member Functions

void updateTolsOnFailure () noexcept
 
void updateTolsOnSuccess () noexcept
 
ALIGATOR_INLINE void setAlmPenalty (Scalar new_mu) noexcept
 Set dual proximal/ALM penalty parameter.
 
void initializeRegularization () noexcept
 
void increaseRegularization () noexcept
 

Detailed Description

template<typename _Scalar>
struct aligator::SolverProxDDPTpl< _Scalar >

A proximal, augmented Lagrangian-type solver for trajectory optimization.

This class implements the Proximal Differential Dynamic Programming algorithm, a variant of the augmented Lagrangian method for trajectory optimization. The paper "PROXDDP: Proximal Constrained Trajectory Optimization" by Jallet et al (2023) is the reference [1] for this implementation.

Definition at line 33 of file solver-proxddp.hpp.

Member Typedef Documentation

◆ Scalar

template<typename _Scalar >
using aligator::SolverProxDDPTpl< _Scalar >::Scalar = _Scalar

Definition at line 37 of file solver-proxddp.hpp.

◆ Problem

template<typename _Scalar >
using aligator::SolverProxDDPTpl< _Scalar >::Problem = TrajOptProblemTpl<Scalar>

Definition at line 39 of file solver-proxddp.hpp.

◆ Workspace

template<typename _Scalar >
using aligator::SolverProxDDPTpl< _Scalar >::Workspace = WorkspaceTpl<Scalar>

Definition at line 40 of file solver-proxddp.hpp.

◆ Results

template<typename _Scalar >
using aligator::SolverProxDDPTpl< _Scalar >::Results = ResultsTpl<Scalar>

Definition at line 41 of file solver-proxddp.hpp.

◆ StageFunctionData

template<typename _Scalar >
using aligator::SolverProxDDPTpl< _Scalar >::StageFunctionData = StageFunctionDataTpl<Scalar>

Definition at line 42 of file solver-proxddp.hpp.

◆ DynamicsData

template<typename _Scalar >
using aligator::SolverProxDDPTpl< _Scalar >::DynamicsData = DynamicsDataTpl<Scalar>

Definition at line 43 of file solver-proxddp.hpp.

◆ CostData

template<typename _Scalar >
using aligator::SolverProxDDPTpl< _Scalar >::CostData = CostDataAbstractTpl<Scalar>

Definition at line 44 of file solver-proxddp.hpp.

◆ StageModel

template<typename _Scalar >
using aligator::SolverProxDDPTpl< _Scalar >::StageModel = StageModelTpl<Scalar>

Definition at line 45 of file solver-proxddp.hpp.

◆ StageData

template<typename _Scalar >
using aligator::SolverProxDDPTpl< _Scalar >::StageData = StageDataTpl<Scalar>

Definition at line 46 of file solver-proxddp.hpp.

◆ CallbackPtr

template<typename _Scalar >
using aligator::SolverProxDDPTpl< _Scalar >::CallbackPtr = shared_ptr<CallbackBaseTpl<Scalar>>

Definition at line 47 of file solver-proxddp.hpp.

◆ CallbackMap

template<typename _Scalar >
using aligator::SolverProxDDPTpl< _Scalar >::CallbackMap = boost::unordered_map<std::string, CallbackPtr>

Definition at line 48 of file solver-proxddp.hpp.

◆ ConstraintStack

template<typename _Scalar >
using aligator::SolverProxDDPTpl< _Scalar >::ConstraintStack = ConstraintStackTpl<Scalar>

Definition at line 49 of file solver-proxddp.hpp.

◆ CstrSet

template<typename _Scalar >
using aligator::SolverProxDDPTpl< _Scalar >::CstrSet = ConstraintSetTpl<Scalar>

Definition at line 50 of file solver-proxddp.hpp.

◆ TrajOptData

template<typename _Scalar >
using aligator::SolverProxDDPTpl< _Scalar >::TrajOptData = TrajOptDataTpl<Scalar>

Definition at line 51 of file solver-proxddp.hpp.

◆ LinesearchOptions

template<typename _Scalar >
using aligator::SolverProxDDPTpl< _Scalar >::LinesearchOptions = typename Linesearch<Scalar>::Options

Definition at line 52 of file solver-proxddp.hpp.

◆ LinesearchType

template<typename _Scalar >
using aligator::SolverProxDDPTpl< _Scalar >::LinesearchType = proxsuite::nlp::ArmijoLinesearch<Scalar>

Definition at line 53 of file solver-proxddp.hpp.

◆ Filter

template<typename _Scalar >
using aligator::SolverProxDDPTpl< _Scalar >::Filter = FilterTpl<Scalar>

Definition at line 54 of file solver-proxddp.hpp.

Constructor & Destructor Documentation

◆ SolverProxDDPTpl()

template<typename _Scalar >
aligator::SolverProxDDPTpl< _Scalar >::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 )

Member Function Documentation

◆ ALIGATOR_DYNAMIC_TYPEDEFS()

template<typename _Scalar >
aligator::SolverProxDDPTpl< _Scalar >::ALIGATOR_DYNAMIC_TYPEDEFS ( Scalar )

◆ getNumThreads()

template<typename _Scalar >
std::size_t aligator::SolverProxDDPTpl< _Scalar >::getNumThreads ( ) const
inline

Definition at line 172 of file solver-proxddp.hpp.

◆ setNumThreads()

template<typename _Scalar >
void aligator::SolverProxDDPTpl< _Scalar >::setNumThreads ( const std::size_t num_threads)

◆ getDualTolerance()

template<typename _Scalar >
Scalar aligator::SolverProxDDPTpl< _Scalar >::getDualTolerance ( ) const
inline

Definition at line 175 of file solver-proxddp.hpp.

◆ setDualTolerance()

template<typename _Scalar >
void aligator::SolverProxDDPTpl< _Scalar >::setDualTolerance ( const Scalar tol)
inline

Manually set desired dual feasibility tolerance.

Definition at line 177 of file solver-proxddp.hpp.

◆ tryLinearStep()

template<typename _Scalar >
Scalar aligator::SolverProxDDPTpl< _Scalar >::tryLinearStep ( const Problem & problem,
const Scalar alpha )

Try a step of size \(\alpha\).

Returns
A primal-dual trial point \((\bfx \oplus\alpha\delta\bfx, \bfu+\alpha\delta\bfu, \bmlam+\alpha\delta\bmlam)\)
The trajectory cost.

◆ tryNonlinearRollout()

template<typename _Scalar >
Scalar aligator::SolverProxDDPTpl< _Scalar >::tryNonlinearRollout ( const Problem & problem,
const Scalar alpha )

Policy rollout using the full nonlinear dynamics. The feedback gains need to be computed first. This will evaluate all the terms in the problem into the problem data, similar to TrajOptProblemTpl::evaluate().

Returns
The trajectory cost.

◆ forwardPass()

template<typename _Scalar >
Scalar aligator::SolverProxDDPTpl< _Scalar >::forwardPass ( const Problem & problem,
const Scalar alpha )

◆ updateLQSubproblem()

template<typename _Scalar >
void aligator::SolverProxDDPTpl< _Scalar >::updateLQSubproblem ( )

◆ setup()

template<typename _Scalar >
void aligator::SolverProxDDPTpl< _Scalar >::setup ( const Problem & problem)

Allocate new workspace and results instances according to the specifications of problem.

Parameters
problemThe problem instance with respect to which memory will be allocated.

◆ cycleProblem()

template<typename _Scalar >
void aligator::SolverProxDDPTpl< _Scalar >::cycleProblem ( const Problem & problem,
shared_ptr< StageDataTpl< Scalar > > data )

◆ run()

template<typename _Scalar >
bool aligator::SolverProxDDPTpl< _Scalar >::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.

Parameters
problemThe trajectory optimization problem to solve.
xs_initInitial trajectory guess.
us_initInitial control sequence guess.
vs_initInitial path multiplier guess.
lams_initInitial co-state guess.
Precondition
You must call SolverProxDDP::setup beforehand to allocate a workspace and results.

◆ innerLoop()

template<typename _Scalar >
bool aligator::SolverProxDDPTpl< _Scalar >::innerLoop ( const Problem & problem)

Perform the inner loop of the algorithm (augmented Lagrangian minimization).

◆ computeInfeasibilities()

template<typename _Scalar >
void aligator::SolverProxDDPTpl< _Scalar >::computeInfeasibilities ( const Problem & problem)

Compute the primal infeasibility measures.

Warning
This will alter the constraint values (by projecting on the normal cone in-place). Compute anything which accesses these before!

◆ computeCriterion()

template<typename _Scalar >
void aligator::SolverProxDDPTpl< _Scalar >::computeCriterion ( )

Compute stationarity criterion (dual infeasibility).

◆ registerCallback()

template<typename _Scalar >
void aligator::SolverProxDDPTpl< _Scalar >::registerCallback ( const std::string & name,
CallbackPtr cb )

Add a callback to the solver instance.

◆ clearCallbacks()

template<typename _Scalar >
void aligator::SolverProxDDPTpl< _Scalar >::clearCallbacks ( )
inlinenoexcept

Remove all callbacks from the instance.

Definition at line 239 of file solver-proxddp.hpp.

◆ getCallbacks()

template<typename _Scalar >
const CallbackMap & aligator::SolverProxDDPTpl< _Scalar >::getCallbacks ( ) const
inline

Definition at line 241 of file solver-proxddp.hpp.

◆ removeCallback()

template<typename _Scalar >
void aligator::SolverProxDDPTpl< _Scalar >::removeCallback ( const std::string & name)
inline

Definition at line 242 of file solver-proxddp.hpp.

◆ getCallbackNames()

template<typename _Scalar >
auto aligator::SolverProxDDPTpl< _Scalar >::getCallbackNames ( ) const
inline

Definition at line 243 of file solver-proxddp.hpp.

◆ getCallback()

template<typename _Scalar >
CallbackPtr aligator::SolverProxDDPTpl< _Scalar >::getCallback ( const std::string & name) const
inline

Definition at line 251 of file solver-proxddp.hpp.

◆ invokeCallbacks()

template<typename _Scalar >
void aligator::SolverProxDDPTpl< _Scalar >::invokeCallbacks ( Workspace & workspace,
Results & results )
inline

Invoke callbacks.

Definition at line 260 of file solver-proxddp.hpp.

◆ computeMultipliers()

template<typename _Scalar >
bool aligator::SolverProxDDPTpl< _Scalar >::computeMultipliers ( const Problem & problem,
const std::vector< VectorXs > & lams,
const std::vector< VectorXs > & vs )

Compute the merit function and stopping criterion dual terms: first-order Lagrange multiplier estimates, shifted and projected constraints.

Returns
bool: whether the op succeeded.

◆ mudyn()

template<typename _Scalar >
ALIGATOR_INLINE Scalar aligator::SolverProxDDPTpl< _Scalar >::mudyn ( ) const
inline

Definition at line 275 of file solver-proxddp.hpp.

◆ mu()

template<typename _Scalar >
ALIGATOR_INLINE Scalar aligator::SolverProxDDPTpl< _Scalar >::mu ( ) const
inline

Definition at line 278 of file solver-proxddp.hpp.

◆ mu_inv()

template<typename _Scalar >
ALIGATOR_INLINE Scalar aligator::SolverProxDDPTpl< _Scalar >::mu_inv ( ) const
inline

Definition at line 279 of file solver-proxddp.hpp.

◆ updateGains()

template<typename _Scalar >
void aligator::SolverProxDDPTpl< _Scalar >::updateGains ( )
inline

Update primal-dual feedback gains (control, costate, path multiplier)

◆ updateTolsOnFailure()

template<typename _Scalar >
void aligator::SolverProxDDPTpl< _Scalar >::updateTolsOnFailure ( )
inlineprotectednoexcept

Definition at line 286 of file solver-proxddp.hpp.

◆ updateTolsOnSuccess()

template<typename _Scalar >
void aligator::SolverProxDDPTpl< _Scalar >::updateTolsOnSuccess ( )
inlineprotectednoexcept

Definition at line 292 of file solver-proxddp.hpp.

◆ setAlmPenalty()

template<typename _Scalar >
ALIGATOR_INLINE void aligator::SolverProxDDPTpl< _Scalar >::setAlmPenalty ( Scalar new_mu)
inlineprotectednoexcept

Set dual proximal/ALM penalty parameter.

Definition at line 299 of file solver-proxddp.hpp.

◆ initializeRegularization()

template<typename _Scalar >
void aligator::SolverProxDDPTpl< _Scalar >::initializeRegularization ( )
inlineprotectednoexcept

Definition at line 306 of file solver-proxddp.hpp.

◆ increaseRegularization()

template<typename _Scalar >
void aligator::SolverProxDDPTpl< _Scalar >::increaseRegularization ( )
inlineprotectednoexcept

Definition at line 316 of file solver-proxddp.hpp.

Member Data Documentation

◆ inner_tol_

template<typename _Scalar >
Scalar aligator::SolverProxDDPTpl< _Scalar >::inner_tol_

Subproblem tolerance.

Definition at line 74 of file solver-proxddp.hpp.

◆ prim_tol_

template<typename _Scalar >
Scalar aligator::SolverProxDDPTpl< _Scalar >::prim_tol_

Desired primal feasibility (for each outer loop)

Definition at line 76 of file solver-proxddp.hpp.

◆ target_tol_

template<typename _Scalar >
Scalar aligator::SolverProxDDPTpl< _Scalar >::target_tol_ = 1e-6

Solver tolerance \(\epsilon > 0\). When sync_dual_tol is false, this will be the desired primal feasibility, where the dual feasibility tolerance is controlled by SolverProxDDPTpl::target_tol_dual.

Definition at line 80 of file solver-proxddp.hpp.

◆ mu_init

template<typename _Scalar >
Scalar aligator::SolverProxDDPTpl< _Scalar >::mu_init = 0.01

Definition at line 91 of file solver-proxddp.hpp.

◆ reg_min

template<typename _Scalar >
Scalar aligator::SolverProxDDPTpl< _Scalar >::reg_min = 1e-10

Definition at line 95 of file solver-proxddp.hpp.

◆ reg_max

template<typename _Scalar >
Scalar aligator::SolverProxDDPTpl< _Scalar >::reg_max = 1e9

Definition at line 96 of file solver-proxddp.hpp.

◆ reg_init

template<typename _Scalar >
Scalar aligator::SolverProxDDPTpl< _Scalar >::reg_init = 1e-9

Definition at line 97 of file solver-proxddp.hpp.

◆ reg_inc_k_

template<typename _Scalar >
Scalar aligator::SolverProxDDPTpl< _Scalar >::reg_inc_k_ = 10.

Definition at line 98 of file solver-proxddp.hpp.

◆ reg_inc_first_k_

template<typename _Scalar >
Scalar aligator::SolverProxDDPTpl< _Scalar >::reg_inc_first_k_ = 100.

Definition at line 99 of file solver-proxddp.hpp.

◆ reg_dec_k_

template<typename _Scalar >
Scalar aligator::SolverProxDDPTpl< _Scalar >::reg_dec_k_ = 1. / 3.

Definition at line 100 of file solver-proxddp.hpp.

◆ preg_

template<typename _Scalar >
Scalar aligator::SolverProxDDPTpl< _Scalar >::preg_ = reg_init

Definition at line 101 of file solver-proxddp.hpp.

◆ preg_last_

template<typename _Scalar >
Scalar aligator::SolverProxDDPTpl< _Scalar >::preg_last_ = 0.

Definition at line 102 of file solver-proxddp.hpp.

◆ inner_tol0

template<typename _Scalar >
Scalar aligator::SolverProxDDPTpl< _Scalar >::inner_tol0 = 1.

Definition at line 106 of file solver-proxddp.hpp.

◆ prim_tol0

template<typename _Scalar >
Scalar aligator::SolverProxDDPTpl< _Scalar >::prim_tol0 = 1.

Definition at line 107 of file solver-proxddp.hpp.

◆ logger

template<typename _Scalar >
Logger aligator::SolverProxDDPTpl< _Scalar >::logger {}

Logger.

Definition at line 110 of file solver-proxddp.hpp.

◆ verbose_

template<typename _Scalar >
VerboseLevel aligator::SolverProxDDPTpl< _Scalar >::verbose_

Solver verbosity level.

Definition at line 113 of file solver-proxddp.hpp.

◆ linear_solver_choice

template<typename _Scalar >
LQSolverChoice aligator::SolverProxDDPTpl< _Scalar >::linear_solver_choice = LQSolverChoice::SERIAL

Choice of linear solver.

Definition at line 115 of file solver-proxddp.hpp.

◆ lq_print_detailed

template<typename _Scalar >
bool aligator::SolverProxDDPTpl< _Scalar >::lq_print_detailed = false

Definition at line 116 of file solver-proxddp.hpp.

◆ hess_approx_

template<typename _Scalar >
HessianApprox aligator::SolverProxDDPTpl< _Scalar >::hess_approx_ = HessianApprox::GAUSS_NEWTON

Type of Hessian approximation. Default is Gauss-Newton.

Definition at line 118 of file solver-proxddp.hpp.

◆ ls_params

template<typename _Scalar >
LinesearchOptions aligator::SolverProxDDPTpl< _Scalar >::ls_params

Linesearch options, as in proxsuite-nlp.

Definition at line 120 of file solver-proxddp.hpp.

◆ ls_strat

template<typename _Scalar >
LinesearchStrategy aligator::SolverProxDDPTpl< _Scalar >::ls_strat = LinesearchStrategy::ARMIJO

Type of linesearch strategy. Default is Armijo.

Definition at line 122 of file solver-proxddp.hpp.

◆ multiplier_update_mode

template<typename _Scalar >
MultiplierUpdateMode aligator::SolverProxDDPTpl< _Scalar >::multiplier_update_mode = MultiplierUpdateMode::NEWTON

Type of Lagrange multiplier update.

Definition at line 124 of file solver-proxddp.hpp.

◆ ls_mode

template<typename _Scalar >
LinesearchMode aligator::SolverProxDDPTpl< _Scalar >::ls_mode = LinesearchMode::PRIMAL

Linesearch mode.

Definition at line 126 of file solver-proxddp.hpp.

◆ dual_weight

template<typename _Scalar >
Scalar aligator::SolverProxDDPTpl< _Scalar >::dual_weight = 1.0

Weight of the dual variables in the primal-dual linesearch.

Definition at line 128 of file solver-proxddp.hpp.

◆ rollout_type_

template<typename _Scalar >
RolloutType aligator::SolverProxDDPTpl< _Scalar >::rollout_type_ = RolloutType::NONLINEAR

Type of rollout for the forward pass.

Definition at line 130 of file solver-proxddp.hpp.

◆ bcl_params

template<typename _Scalar >
AlmParams aligator::SolverProxDDPTpl< _Scalar >::bcl_params

Parameters for the BCL outer loop of the augmented Lagrangian algorithm.

Definition at line 132 of file solver-proxddp.hpp.

◆ sa_strategy

template<typename _Scalar >
StepAcceptanceStrategy aligator::SolverProxDDPTpl< _Scalar >::sa_strategy = StepAcceptanceStrategy::LINESEARCH

Step acceptance mode.

Definition at line 134 of file solver-proxddp.hpp.

◆ force_initial_condition_

template<typename _Scalar >
bool aligator::SolverProxDDPTpl< _Scalar >::force_initial_condition_ = true

Force the initial state \( x_0 \) to be fixed to the problem initial condition.

Definition at line 138 of file solver-proxddp.hpp.

◆ max_refinement_steps_

template<typename _Scalar >
std::size_t aligator::SolverProxDDPTpl< _Scalar >::max_refinement_steps_
Initial value:
=
0

Definition at line 140 of file solver-proxddp.hpp.

◆ refinement_threshold_

template<typename _Scalar >
Scalar aligator::SolverProxDDPTpl< _Scalar >::refinement_threshold_ = 1e-13

Definition at line 142 of file solver-proxddp.hpp.

◆ max_iters

template<typename _Scalar >
std::size_t aligator::SolverProxDDPTpl< _Scalar >::max_iters

Definition at line 143 of file solver-proxddp.hpp.

◆ max_al_iters

template<typename _Scalar >
std::size_t aligator::SolverProxDDPTpl< _Scalar >::max_al_iters = 100

Definition at line 144 of file solver-proxddp.hpp.

◆ rollout_max_iters

template<typename _Scalar >
uint aligator::SolverProxDDPTpl< _Scalar >::rollout_max_iters

Definition at line 145 of file solver-proxddp.hpp.

◆ workspace_

template<typename _Scalar >
Workspace aligator::SolverProxDDPTpl< _Scalar >::workspace_

Definition at line 147 of file solver-proxddp.hpp.

◆ results_

template<typename _Scalar >
Results aligator::SolverProxDDPTpl< _Scalar >::results_

Definition at line 148 of file solver-proxddp.hpp.

◆ linearSolver_

template<typename _Scalar >
std::unique_ptr<gar::RiccatiSolverBase<Scalar> > aligator::SolverProxDDPTpl< _Scalar >::linearSolver_

LQR subproblem solver.

Definition at line 150 of file solver-proxddp.hpp.

◆ filter_

template<typename _Scalar >
Filter aligator::SolverProxDDPTpl< _Scalar >::filter_

Definition at line 151 of file solver-proxddp.hpp.

◆ linesearch_

template<typename _Scalar >
LinesearchType aligator::SolverProxDDPTpl< _Scalar >::linesearch_

Linesearch function.

Definition at line 153 of file solver-proxddp.hpp.


The documentation for this struct was generated from the following files: