Public Member Functions | Protected Member Functions | Protected Attributes | List of all members
exotica::AbstractDDPSolver Class Referenceabstract

#include <abstract_ddp_solver.h>

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

Public Member Functions

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)
 
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::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
virtual std::vector< InitializerGetAllTemplates () const =0
 
virtual Initializer GetInitializerTemplate ()=0
 
 InstantiableBase ()=default
 
virtual void InstantiateInternal (const Initializer &init)=0
 
virtual ~InstantiableBase ()=default
 

Protected Member Functions

virtual void BackwardPass ()=0
 Computes the control gains for a the trajectory in the associated DynamicTimeIndexedProblem. More...
 
virtual void DecreaseRegularization ()
 
double ForwardPass (const double alpha)
 Forward simulates the dynamics using the gains computed in the last BackwardPass;. More...
 
virtual void IncreaseRegularization ()
 

Protected Attributes

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_
 

Additional Inherited Members

- Public Attributes inherited from exotica::Object
bool debug_
 
std::string ns_
 
std::string object_name_
 

Detailed Description

Definition at line 43 of file abstract_ddp_solver.h.

Member Function Documentation

virtual void exotica::AbstractDDPSolver::BackwardPass ( )
protectedpure virtual

Computes the control gains for a the trajectory in the associated DynamicTimeIndexedProblem.

Implemented in exotica::AbstractFeasibilityDrivenDDPSolver, exotica::AnalyticDDPSolver, and exotica::ControlLimitedDDPSolver.

virtual void exotica::AbstractDDPSolver::DecreaseRegularization ( )
inlineprotectedvirtual

Reimplemented in exotica::AbstractFeasibilityDrivenDDPSolver.

Definition at line 108 of file abstract_ddp_solver.h.

double exotica::AbstractDDPSolver::ForwardPass ( const double  alpha)
protected

Forward simulates the dynamics using the gains computed in the last BackwardPass;.

Parameters
alphaThe learning rate.
ref_trajectoryThe reference state trajectory.
Returns
The cost associated with the new control and state trajectory.

Definition at line 281 of file abstract_ddp_solver.cpp.

std::vector< double > exotica::AbstractDDPSolver::get_control_cost_evolution ( ) const

Definition at line 334 of file abstract_ddp_solver.cpp.

const std::vector< Eigen::MatrixXd > & exotica::AbstractDDPSolver::get_fu ( ) const

Definition at line 333 of file abstract_ddp_solver.cpp.

const std::vector< Eigen::MatrixXd > & exotica::AbstractDDPSolver::get_fx ( ) const

Definition at line 332 of file abstract_ddp_solver.cpp.

const std::vector< Eigen::MatrixXd > & exotica::AbstractDDPSolver::get_K ( ) const

Definition at line 325 of file abstract_ddp_solver.cpp.

const std::vector< Eigen::VectorXd > & exotica::AbstractDDPSolver::get_k ( ) const

Definition at line 326 of file abstract_ddp_solver.cpp.

const std::vector< Eigen::VectorXd > & exotica::AbstractDDPSolver::get_Qu ( ) const

Definition at line 324 of file abstract_ddp_solver.cpp.

const std::vector< Eigen::MatrixXd > & exotica::AbstractDDPSolver::get_Quu ( ) const

Definition at line 322 of file abstract_ddp_solver.cpp.

const std::vector< Eigen::MatrixXd > & exotica::AbstractDDPSolver::get_Quu_inv ( ) const

Definition at line 331 of file abstract_ddp_solver.cpp.

const std::vector< Eigen::MatrixXd > & exotica::AbstractDDPSolver::get_Qux ( ) const

Definition at line 321 of file abstract_ddp_solver.cpp.

const std::vector< Eigen::VectorXd > & exotica::AbstractDDPSolver::get_Qx ( ) const

Definition at line 323 of file abstract_ddp_solver.cpp.

const std::vector< Eigen::MatrixXd > & exotica::AbstractDDPSolver::get_Qxx ( ) const

Definition at line 320 of file abstract_ddp_solver.cpp.

std::vector< double > exotica::AbstractDDPSolver::get_regularization_evolution ( ) const

Definition at line 374 of file abstract_ddp_solver.cpp.

std::vector< double > exotica::AbstractDDPSolver::get_steplength_evolution ( ) const

Definition at line 362 of file abstract_ddp_solver.cpp.

const std::vector< Eigen::VectorXd > & exotica::AbstractDDPSolver::get_U_ref ( ) const

Definition at line 330 of file abstract_ddp_solver.cpp.

const std::vector< Eigen::VectorXd > & exotica::AbstractDDPSolver::get_U_try ( ) const

Definition at line 328 of file abstract_ddp_solver.cpp.

const std::vector< Eigen::VectorXd > & exotica::AbstractDDPSolver::get_Vx ( ) const

Definition at line 319 of file abstract_ddp_solver.cpp.

const std::vector< Eigen::MatrixXd > & exotica::AbstractDDPSolver::get_Vxx ( ) const

Definition at line 318 of file abstract_ddp_solver.cpp.

const std::vector< Eigen::VectorXd > & exotica::AbstractDDPSolver::get_X_ref ( ) const

Definition at line 329 of file abstract_ddp_solver.cpp.

const std::vector< Eigen::VectorXd > & exotica::AbstractDDPSolver::get_X_try ( ) const

Definition at line 327 of file abstract_ddp_solver.cpp.

Eigen::VectorXd exotica::AbstractDDPSolver::GetFeedbackControl ( Eigen::VectorXdRefConst  x,
int  t 
) const
overridevirtual

Implements exotica::FeedbackMotionSolver.

Definition at line 312 of file abstract_ddp_solver.cpp.

virtual void exotica::AbstractDDPSolver::IncreaseRegularization ( )
inlineprotectedvirtual

Reimplemented in exotica::AbstractFeasibilityDrivenDDPSolver.

Definition at line 103 of file abstract_ddp_solver.h.

void exotica::AbstractDDPSolver::set_control_cost_evolution ( const int  index,
const double  cost 
)

Definition at line 346 of file abstract_ddp_solver.cpp.

void exotica::AbstractDDPSolver::Solve ( Eigen::MatrixXd &  solution)
overridevirtual

Solves the problem.

Parameters
solutionReturned solution trajectory as a vector of joint configurations.

Implements exotica::MotionSolver.

Reimplemented in exotica::AbstractFeasibilityDrivenDDPSolver.

Definition at line 34 of file abstract_ddp_solver.cpp.

void exotica::AbstractDDPSolver::SpecifyProblem ( PlanningProblemPtr  pointer)
overridevirtual

Binds the solver to a specific problem which must be pre-initalised.

Parameters
pointerShared pointer to the motion planning problem
Returns
Successful if the problem is a valid DynamicTimeIndexedProblem

Reimplemented from exotica::MotionSolver.

Reimplemented in exotica::AbstractFeasibilityDrivenDDPSolver.

Definition at line 261 of file abstract_ddp_solver.cpp.

Member Data Documentation

double exotica::AbstractDDPSolver::alpha_best_
protected

Line-search step taken.

Definition at line 129 of file abstract_ddp_solver.h.

Eigen::VectorXd exotica::AbstractDDPSolver::alpha_space_
protected

Backtracking line-search steplengths.

Definition at line 114 of file abstract_ddp_solver.h.

AbstractDDPSolverInitializer exotica::AbstractDDPSolver::base_parameters_
protected

Definition at line 101 of file abstract_ddp_solver.h.

double exotica::AbstractDDPSolver::control_cost_
protected

Control cost during iteration.

Definition at line 123 of file abstract_ddp_solver.h.

std::vector<double> exotica::AbstractDDPSolver::control_cost_evolution_
protected

Evolution of the control cost (control regularization)

Definition at line 152 of file abstract_ddp_solver.h.

double exotica::AbstractDDPSolver::control_cost_try_
protected

Total control cost computed by line-search procedure.

Definition at line 126 of file abstract_ddp_solver.h.

double exotica::AbstractDDPSolver::cost_
protected

Cost during iteration.

Definition at line 122 of file abstract_ddp_solver.h.

double exotica::AbstractDDPSolver::cost_prev_
protected

Cost during previous iteration.

Definition at line 128 of file abstract_ddp_solver.h.

double exotica::AbstractDDPSolver::cost_try_
protected

Total cost computed by line-search procedure.

Definition at line 125 of file abstract_ddp_solver.h.

double exotica::AbstractDDPSolver::dt_
protected

Integration time-step.

Definition at line 121 of file abstract_ddp_solver.h.

DynamicsSolverPtr exotica::AbstractDDPSolver::dynamics_solver_
protected

Shared pointer to the dynamics solver.

Definition at line 88 of file abstract_ddp_solver.h.

std::vector<Eigen::MatrixXd> exotica::AbstractDDPSolver::fu_
protected

Derivative of the dynamics f w.r.t. u.

Definition at line 150 of file abstract_ddp_solver.h.

std::vector<Eigen::MatrixXd> exotica::AbstractDDPSolver::fx_
protected

Derivative of the dynamics f w.r.t. x.

Definition at line 149 of file abstract_ddp_solver.h.

std::vector<Eigen::MatrixXd> exotica::AbstractDDPSolver::K_
protected

Feedback gains.

Definition at line 139 of file abstract_ddp_solver.h.

std::vector<Eigen::VectorXd> exotica::AbstractDDPSolver::k_
protected

Feed-forward terms.

Definition at line 140 of file abstract_ddp_solver.h.

double exotica::AbstractDDPSolver::lambda_
protected

Regularization (Vxx, Quu)

Definition at line 115 of file abstract_ddp_solver.h.

int exotica::AbstractDDPSolver::NDX_
protected

Size of tangent vector to the state vector.

Definition at line 119 of file abstract_ddp_solver.h.

int exotica::AbstractDDPSolver::NU_
protected

Size of control vector.

Definition at line 117 of file abstract_ddp_solver.h.

int exotica::AbstractDDPSolver::NV_
protected

Size of velocity vector (tangent vector to the configuration)

Definition at line 120 of file abstract_ddp_solver.h.

int exotica::AbstractDDPSolver::NX_
protected

Size of state vector.

Definition at line 118 of file abstract_ddp_solver.h.

DynamicTimeIndexedShootingProblemPtr exotica::AbstractDDPSolver::prob_
protected

Shared pointer to the planning problem.

Definition at line 87 of file abstract_ddp_solver.h.

std::vector<Eigen::VectorXd> exotica::AbstractDDPSolver::Qu_
protected

Gradient of the Hamiltonian.

Definition at line 138 of file abstract_ddp_solver.h.

std::vector<Eigen::MatrixXd> exotica::AbstractDDPSolver::Quu_
protected

Hessian of the Hamiltonian.

Definition at line 136 of file abstract_ddp_solver.h.

std::vector<Eigen::MatrixXd> exotica::AbstractDDPSolver::Quu_inv_
protected

Inverse of the Hessian of the Hamiltonian.

Definition at line 148 of file abstract_ddp_solver.h.

std::vector<Eigen::MatrixXd> exotica::AbstractDDPSolver::Qux_
protected

Hessian of the Hamiltonian.

Definition at line 135 of file abstract_ddp_solver.h.

std::vector<Eigen::VectorXd> exotica::AbstractDDPSolver::Qx_
protected

Gradient of the Hamiltonian.

Definition at line 137 of file abstract_ddp_solver.h.

std::vector<Eigen::MatrixXd> exotica::AbstractDDPSolver::Qxx_
protected

Hessian of the Hamiltonian.

Definition at line 134 of file abstract_ddp_solver.h.

std::vector<double> exotica::AbstractDDPSolver::regularization_evolution_
protected

Evolution of the regularization (xreg/ureg)

Definition at line 154 of file abstract_ddp_solver.h.

std::vector<double> exotica::AbstractDDPSolver::steplength_evolution_
protected

Evolution of the steplength.

Definition at line 153 of file abstract_ddp_solver.h.

int exotica::AbstractDDPSolver::T_
protected

Length of shooting problem, i.e., state trajectory. The control trajectory has length T_-1.

Definition at line 116 of file abstract_ddp_solver.h.

double exotica::AbstractDDPSolver::time_taken_backward_pass_
protected

Definition at line 130 of file abstract_ddp_solver.h.

double exotica::AbstractDDPSolver::time_taken_forward_pass_
protected

Definition at line 130 of file abstract_ddp_solver.h.

std::vector<Eigen::VectorXd> exotica::AbstractDDPSolver::U_ref_
protected

Reference control trajectory for feedback control.

Definition at line 146 of file abstract_ddp_solver.h.

std::vector<Eigen::VectorXd> exotica::AbstractDDPSolver::U_try_
protected

Updated control trajectory during iteration (computed by line-search)

Definition at line 143 of file abstract_ddp_solver.h.

std::vector<Eigen::VectorXd> exotica::AbstractDDPSolver::Vx_
protected

Gradient of the Value function.

Definition at line 133 of file abstract_ddp_solver.h.

std::vector<Eigen::MatrixXd> exotica::AbstractDDPSolver::Vxx_
protected

Hessian of the Value function.

Definition at line 132 of file abstract_ddp_solver.h.

std::vector<Eigen::VectorXd> exotica::AbstractDDPSolver::X_ref_
protected

Reference state trajectory for feedback control.

Definition at line 145 of file abstract_ddp_solver.h.

std::vector<Eigen::VectorXd> exotica::AbstractDDPSolver::X_try_
protected

Updated state trajectory during iteration (computed by line-search)

Definition at line 142 of file abstract_ddp_solver.h.


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