Public Member Functions | Private Member Functions | Private Attributes | List of all members
exotica::ILQGSolver Class Reference

#include <ilqg_solver.h>

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

Public Member Functions

Eigen::VectorXd GetFeedbackControl (Eigen::VectorXdRefConst x, int t) const override
 
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
 InstantiableBase ()=default
 
virtual ~InstantiableBase ()=default
 
- Public Member Functions inherited from exotica::Instantiable< ILQGSolverInitializer >
std::vector< InitializerGetAllTemplates () const override
 
Initializer GetInitializerTemplate () override
 
const ILQGSolverInitializer & GetParameters () const
 
virtual void Instantiate (const ILQGSolverInitializer &init)
 
void InstantiateInternal (const Initializer &init) override
 

Private Member Functions

void BackwardPass ()
 !< Reference trajectory for feedback control. More...
 
double ForwardPass (const double alpha, Eigen::MatrixXdRefConst ref_x, Eigen::MatrixXdRefConst ref_u)
 Forward simulates the dynamics using the gains computed in the last BackwardPass;. More...
 

Private Attributes

Eigen::MatrixXd best_ref_u_
 
Eigen::MatrixXd best_ref_x_
 !< Control gains. More...
 
DynamicsSolverPtr dynamics_solver_
 !< Shared pointer to the planning problem. More...
 
std::vector< Eigen::MatrixXd > L_gains_
 
std::vector< Eigen::MatrixXd > l_gains_
 !< Shared pointer to the dynamics solver. More...
 
DynamicTimeIndexedShootingProblemPtr prob_
 

Additional Inherited Members

- Public Attributes inherited from exotica::Object
bool debug_
 
std::string ns_
 
std::string object_name_
 
- Protected Attributes inherited from exotica::MotionSolver
int max_iterations_
 
double planning_time_
 
PlanningProblemPtr problem_
 
- Protected Attributes inherited from exotica::Instantiable< ILQGSolverInitializer >
ILQGSolverInitializer parameters_
 

Detailed Description

Definition at line 46 of file ilqg_solver.h.

Member Function Documentation

void exotica::ILQGSolver::BackwardPass ( )
private

!< Reference trajectory for feedback control.

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

Definition at line 49 of file ilqg_solver.cpp.

double exotica::ILQGSolver::ForwardPass ( const double  alpha,
Eigen::MatrixXdRefConst  ref_x,
Eigen::MatrixXdRefConst  ref_u 
)
private

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 145 of file ilqg_solver.cpp.

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

Implements exotica::FeedbackMotionSolver.

Definition at line 315 of file ilqg_solver.cpp.

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

Solves the problem.

Parameters
solutionReturned solution trajectory as a vector of joint configurations.

Implements exotica::MotionSolver.

Definition at line 174 of file ilqg_solver.cpp.

void exotica::ILQGSolver::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.

Definition at line 36 of file ilqg_solver.cpp.

Member Data Documentation

Eigen::MatrixXd exotica::ILQGSolver::best_ref_u_
private

Definition at line 65 of file ilqg_solver.h.

Eigen::MatrixXd exotica::ILQGSolver::best_ref_x_
private

!< Control gains.

Definition at line 65 of file ilqg_solver.h.

DynamicsSolverPtr exotica::ILQGSolver::dynamics_solver_
private

!< Shared pointer to the planning problem.

Definition at line 62 of file ilqg_solver.h.

std::vector<Eigen::MatrixXd> exotica::ILQGSolver::L_gains_
private

Definition at line 63 of file ilqg_solver.h.

std::vector<Eigen::MatrixXd> exotica::ILQGSolver::l_gains_
private

!< Shared pointer to the dynamics solver.

Definition at line 63 of file ilqg_solver.h.

DynamicTimeIndexedShootingProblemPtr exotica::ILQGSolver::prob_
private

Definition at line 61 of file ilqg_solver.h.


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


exotica_ilqg_solver
Author(s): Traiko Dinev
autogenerated on Sat Apr 10 2021 02:36:28