30 #ifndef EXOTICA_ILQG_SOLVER_ILQG_SOLVER_H_ 31 #define EXOTICA_ILQG_SOLVER_ILQG_SOLVER_H_ 36 #include <Eigen/Eigenvalues> 38 #include <exotica_ilqg_solver/ilqg_solver_initializer.h> 51 void Solve(Eigen::MatrixXd& solution)
override;
80 #endif // EXOTICA_ILQG_SOLVER_ILQG_SOLVER_H_ DynamicTimeIndexedShootingProblemPtr prob_
std::vector< Eigen::MatrixXd > L_gains_
Eigen::VectorXd GetFeedbackControl(Eigen::VectorXdRefConst x, int t) const override
DynamicsSolverPtr dynamics_solver_
!< Shared pointer to the planning problem.
Eigen::MatrixXd best_ref_u_
std::shared_ptr< exotica::DynamicsSolver > DynamicsSolverPtr
const Eigen::Ref< const Eigen::MatrixXd > & MatrixXdRefConst
void BackwardPass()
!< Reference trajectory for feedback control.
void Solve(Eigen::MatrixXd &solution) override
Solves the problem.
const Eigen::Ref< const Eigen::VectorXd > & VectorXdRefConst
void SpecifyProblem(PlanningProblemPtr pointer) override
Binds the solver to a specific problem which must be pre-initalised.
Eigen::MatrixXd best_ref_x_
!< Control gains.
std::shared_ptr< exotica::DynamicTimeIndexedShootingProblem > DynamicTimeIndexedShootingProblemPtr
std::shared_ptr< PlanningProblem > PlanningProblemPtr
std::vector< Eigen::MatrixXd > l_gains_
!< Shared pointer to the dynamics solver.
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;.