Public Member Functions | List of all members
exotica::FeasibilityDrivenDDPSolver Class Reference

#include <feasibility_driven_ddp_solver.h>

Inheritance diagram for exotica::FeasibilityDrivenDDPSolver:
Inheritance graph
[legend]

Public Member Functions

void Instantiate (const FeasibilityDrivenDDPSolverInitializer &init) override
 
- Public Member Functions inherited from exotica::AbstractFeasibilityDrivenDDPSolver
const std::vector< Eigen::VectorXd > & get_fs () const
 
const std::vector< Eigen::VectorXd > & get_us () const
 
const std::vector< Eigen::VectorXd > & get_xs () const
 
void Solve (Eigen::MatrixXd &solution) override
 Solves the problem. More...
 
void SpecifyProblem (PlanningProblemPtr pointer) override
 Binds the solver to a specific problem which must be pre-initalised. More...
 
- Public Member Functions inherited from exotica::AbstractDDPSolver
std::vector< double > get_control_cost_evolution () const
 
const std::vector< Eigen::MatrixXd > & get_fu () const
 
const std::vector< Eigen::MatrixXd > & get_fx () const
 
const std::vector< Eigen::MatrixXd > & get_K () const
 
const std::vector< Eigen::VectorXd > & get_k () const
 
const std::vector< Eigen::VectorXd > & get_Qu () const
 
const std::vector< Eigen::MatrixXd > & get_Quu () const
 
const std::vector< Eigen::MatrixXd > & get_Quu_inv () const
 
const std::vector< Eigen::MatrixXd > & get_Qux () const
 
const std::vector< Eigen::VectorXd > & get_Qx () const
 
const std::vector< Eigen::MatrixXd > & get_Qxx () const
 
std::vector< double > get_regularization_evolution () const
 
std::vector< double > get_steplength_evolution () const
 
const std::vector< Eigen::VectorXd > & get_U_ref () const
 
const std::vector< Eigen::VectorXd > & get_U_try () const
 
const std::vector< Eigen::VectorXd > & get_Vx () const
 
const std::vector< Eigen::MatrixXd > & get_Vxx () const
 
const std::vector< Eigen::VectorXd > & get_X_ref () const
 
const std::vector< Eigen::VectorXd > & get_X_try () const
 
Eigen::VectorXd GetFeedbackControl (Eigen::VectorXdRefConst x, int t) const override
 
void set_control_cost_evolution (const int index, const double cost)
 
- Public Member Functions inherited from exotica::MotionSolver
int GetNumberOfMaxIterations ()
 
double GetPlanningTime ()
 
PlanningProblemPtr GetProblem () const
 
void InstantiateBase (const Initializer &init) override
 
 MotionSolver ()=default
 
std::string Print (const std::string &prepend) const override
 
void SetNumberOfMaxIterations (int max_iter)
 
virtual ~MotionSolver ()=default
 
- Public Member Functions inherited from exotica::Object
std::string GetObjectName ()
 
void InstantiateObject (const Initializer &init)
 
 Object ()
 
virtual std::string type () const
 
virtual ~Object ()
 
- Public Member Functions inherited from exotica::InstantiableBase
 InstantiableBase ()=default
 
virtual ~InstantiableBase ()=default
 
- Public Member Functions inherited from exotica::Instantiable< FeasibilityDrivenDDPSolverInitializer >
std::vector< InitializerGetAllTemplates () const override
 
Initializer GetInitializerTemplate () override
 
const FeasibilityDrivenDDPSolverInitializer & GetParameters () const
 
void InstantiateInternal (const Initializer &init) override
 

Additional Inherited Members

- Public Attributes inherited from exotica::Object
bool debug_
 
std::string ns_
 
std::string object_name_
 
- Protected Member Functions inherited from exotica::AbstractFeasibilityDrivenDDPSolver
virtual void AllocateData ()
 
void BackwardPass () override
 Computes the control gains for a the trajectory in the associated DynamicTimeIndexedProblem. More...
 
virtual bool BackwardPassFDDP ()
 
double CalcDiff ()
 
double CheckStoppingCriteria ()
 
bool ComputeDirection (const bool recalcDiff)
 
virtual void ComputeGains (const int t)
 
void DecreaseRegularization () override
 
const Eigen::Vector2d & ExpectedImprovement ()
 
void ForwardPass (const double steplength)
 
void IncreaseRegularization () override
 
bool IsNaN (const double value)
 
void SetCandidate (const std::vector< Eigen::VectorXd > &xs_warm, const std::vector< Eigen::VectorXd > &us_warm, const bool is_feasible)
 
double TryStep (const double steplength)
 
void UpdateExpectedImprovement ()
 
- Protected Member Functions inherited from exotica::AbstractDDPSolver
double ForwardPass (const double alpha)
 Forward simulates the dynamics using the gains computed in the last BackwardPass;. More...
 
- Protected Attributes inherited from exotica::AbstractFeasibilityDrivenDDPSolver
bool clamp_to_control_limits_in_forward_pass_ = false
 
Eigen::MatrixXd control_limits_
 
Eigen::Vector2d d_
 LQ approximation of the expected improvement. More...
 
double dg_ = 0.
 
double dq_ = 0.
 
double dV_
 Cost reduction obtained by TryStep. More...
 
double dv_ = 0.
 
double dVexp_
 Expected cost reduction. More...
 
std::vector< Eigen::VectorXd > dx_
 
std::vector< Eigen::VectorXd > fs_
 Gaps/defects between shooting nodes. More...
 
Eigen::VectorXd fTVxx_p_
 
std::vector< Eigen::MatrixXd > FuTVxx_p_
 
Eigen::MatrixXd FxTVxx_p_
 
double initial_regularization_rate_ = 1e-9
 
bool is_feasible_ = false
 
int last_T_ = -1
 
int NDX_
 
std::vector< Eigen::LDLT< Eigen::MatrixXd > > Quu_ldlt_
 
std::vector< Eigen::VectorXd > Quuk_
 
std::vector< Eigen::MatrixXd > Qxu_
 
double regfactor_ = 10.
 Factor by which the regularization gets increased/decreased. More...
 
double regmax_ = 1e9
 Maximum regularization (to exit by divergence) More...
 
double regmin_ = 1e-9
 Minimum regularization (will not decrease lower) More...
 
double steplength_
 Current applied step-length. More...
 
double stop_
 Value computed by CheckStoppingCriteria. More...
 
double th_acceptnegstep_ = 2.
 Threshold used for accepting step along ascent direction. More...
 
double th_acceptstep_ = 0.1
 Threshold used for accepting step. More...
 
double th_grad_ = 1e-12
 Tolerance of the expected gradient used for testing the step. More...
 
double th_gradient_tolerance_ = 0.
 Gradient tolerance. More...
 
double th_stepdec_ = 0.5
 Step-length threshold used to decrease regularization. More...
 
double th_stepinc_ = 0.01
 Step-length threshold used to increase regularization. More...
 
double th_stop_ = 1e-9
 Tolerance for stopping the algorithm. More...
 
double ureg_ = 1e-9
 Control regularization. More...
 
std::vector< Eigen::VectorXd > us_
 
std::vector< Eigen::VectorXd > us_try_
 Control trajectory computed by line-search procedure. More...
 
bool was_feasible_ = false
 Label that indicates in the previous iterate was feasible. More...
 
Eigen::VectorXd xnext_
 
double xreg_ = 1e-9
 State regularization. More...
 
std::vector< Eigen::VectorXd > xs_
 
std::vector< Eigen::VectorXd > xs_try_
 State trajectory computed by line-search procedure. More...
 
- Protected Attributes inherited from exotica::AbstractDDPSolver
double alpha_best_
 Line-search step taken. More...
 
Eigen::VectorXd alpha_space_
 Backtracking line-search steplengths. More...
 
AbstractDDPSolverInitializer base_parameters_
 
double control_cost_
 Control cost during iteration. More...
 
std::vector< double > control_cost_evolution_
 Evolution of the control cost (control regularization) More...
 
double control_cost_try_
 Total control cost computed by line-search procedure. More...
 
double cost_
 Cost during iteration. More...
 
double cost_prev_
 Cost during previous iteration. More...
 
double cost_try_
 Total cost computed by line-search procedure. More...
 
double dt_
 Integration time-step. More...
 
DynamicsSolverPtr dynamics_solver_
 Shared pointer to the dynamics solver. More...
 
std::vector< Eigen::MatrixXd > fu_
 Derivative of the dynamics f w.r.t. u. More...
 
std::vector< Eigen::MatrixXd > fx_
 Derivative of the dynamics f w.r.t. x. More...
 
std::vector< Eigen::MatrixXd > K_
 Feedback gains. More...
 
std::vector< Eigen::VectorXd > k_
 Feed-forward terms. More...
 
double lambda_
 Regularization (Vxx, Quu) More...
 
int NDX_
 Size of tangent vector to the state vector. More...
 
int NU_
 Size of control vector. More...
 
int NV_
 Size of velocity vector (tangent vector to the configuration) More...
 
int NX_
 Size of state vector. More...
 
DynamicTimeIndexedShootingProblemPtr prob_
 Shared pointer to the planning problem. More...
 
std::vector< Eigen::VectorXd > Qu_
 Gradient of the Hamiltonian. More...
 
std::vector< Eigen::MatrixXd > Quu_
 Hessian of the Hamiltonian. More...
 
std::vector< Eigen::MatrixXd > Quu_inv_
 Inverse of the Hessian of the Hamiltonian. More...
 
std::vector< Eigen::MatrixXd > Qux_
 Hessian of the Hamiltonian. More...
 
std::vector< Eigen::VectorXd > Qx_
 Gradient of the Hamiltonian. More...
 
std::vector< Eigen::MatrixXd > Qxx_
 Hessian of the Hamiltonian. More...
 
std::vector< double > regularization_evolution_
 Evolution of the regularization (xreg/ureg) More...
 
std::vector< double > steplength_evolution_
 Evolution of the steplength. More...
 
int T_
 Length of shooting problem, i.e., state trajectory. The control trajectory has length T_-1. More...
 
double time_taken_backward_pass_
 
double time_taken_forward_pass_
 
std::vector< Eigen::VectorXd > U_ref_
 Reference control trajectory for feedback control. More...
 
std::vector< Eigen::VectorXd > U_try_
 Updated control trajectory during iteration (computed by line-search) More...
 
std::vector< Eigen::VectorXd > Vx_
 Gradient of the Value function. More...
 
std::vector< Eigen::MatrixXd > Vxx_
 Hessian of the Value function. More...
 
std::vector< Eigen::VectorXd > X_ref_
 Reference state trajectory for feedback control. More...
 
std::vector< Eigen::VectorXd > X_try_
 Updated state trajectory during iteration (computed by line-search) More...
 
- Protected Attributes inherited from exotica::MotionSolver
int max_iterations_
 
double planning_time_
 
PlanningProblemPtr problem_
 
- Protected Attributes inherited from exotica::Instantiable< FeasibilityDrivenDDPSolverInitializer >
FeasibilityDrivenDDPSolverInitializer parameters_
 

Detailed Description

Definition at line 129 of file feasibility_driven_ddp_solver.h.

Member Function Documentation

void exotica::FeasibilityDrivenDDPSolver::Instantiate ( const FeasibilityDrivenDDPSolverInitializer &  init)
overridevirtual

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


exotica_ddp_solver
Author(s): Traiko Dinev
autogenerated on Sat Apr 10 2021 02:36:22