|
robotoc
robotoc - efficient ROBOT Optimal Control solvers
|
Optimal control problem solver of unconstrained rigid-body systems by Riccati recursion. "Unconstrained" means that the system does not have either a floating base or any contacts. More...
#include <unconstr_ocp_solver.hpp>
Public Member Functions | |
| UnconstrOCPSolver (const OCP &ocp, const SolverOptions &solver_options=SolverOptions()) | |
| Construct optimal control problem solver. More... | |
| UnconstrOCPSolver () | |
| Default constructor. More... | |
| ~UnconstrOCPSolver ()=default | |
| Destructor. More... | |
| UnconstrOCPSolver (const UnconstrOCPSolver &)=default | |
| Default copy constructor. More... | |
| UnconstrOCPSolver & | operator= (const UnconstrOCPSolver &)=default |
| Default copy assign operator. More... | |
| UnconstrOCPSolver (UnconstrOCPSolver &&) noexcept=default | |
| Default move constructor. More... | |
| UnconstrOCPSolver & | operator= (UnconstrOCPSolver &&) noexcept=default |
| Default move assign operator. More... | |
| void | setSolverOptions (const SolverOptions &solver_options) |
| Sets the solver option. More... | |
| void | discretize (const double t) |
| Discretizes the problem and reiszes the data structures. More... | |
| void | initConstraints () |
| Initializes the priaml-dual interior point method for inequality constraints. More... | |
| void | solve (const double t, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const bool init_solver=true) |
| Solves the optimal control problem. Internally calls updateSolution(). More... | |
| const SolverStatistics & | getSolverStatistics () const |
| Gets the solver statistics. More... | |
| const SplitSolution & | getSolution (const int stage) const |
| Get the split solution of a time stage. For example, the control input torques at the initial stage can be obtained by ocp.getSolution(0).u. More... | |
| std::vector< Eigen::VectorXd > | getSolution (const std::string &name) const |
| Get the solution vector over the horizon. More... | |
| const std::vector< LQRPolicy > & | getLQRPolicy () const |
| Gets of the local LQR policies over the horizon. More... | |
| void | setSolution (const std::string &name, const Eigen::VectorXd &value) |
| Sets the solution over the horizon. More... | |
| double | KKTError (const double t, const Eigen::VectorXd &q, const Eigen::VectorXd &v) |
| Computes the KKT residual of the optimal control problem and returns the KKT error, that is, the l2-norm of the KKT residual. More... | |
| double | KKTError () const |
| Returns the l2-norm of the KKT residuals using the results of UnconstrOCPsolver::updateSolution() or UnconstrOCPsolver::solve(). More... | |
| const std::vector< GridInfo > & | getTimeDiscretization () const |
| Gets the discretization. More... | |
| void | setRobotProperties (const RobotProperties &properties) |
| Sets a collection of the properties for robot model in this solver. More... | |
Optimal control problem solver of unconstrained rigid-body systems by Riccati recursion. "Unconstrained" means that the system does not have either a floating base or any contacts.
| robotoc::UnconstrOCPSolver::UnconstrOCPSolver | ( | const OCP & | ocp, |
| const SolverOptions & | solver_options = SolverOptions() |
||
| ) |
Construct optimal control problem solver.
| [in] | ocp | Optimal control problem. |
| [in] | solver_options | Solver options. Default is SolverOptions(). |
| robotoc::UnconstrOCPSolver::UnconstrOCPSolver | ( | ) |
Default constructor.
|
default |
Destructor.
|
default |
Default copy constructor.
|
defaultnoexcept |
Default move constructor.
| void robotoc::UnconstrOCPSolver::discretize | ( | const double | t | ) |
Discretizes the problem and reiszes the data structures.
| [in] | t | Initial time of the horizon. |
| const std::vector< LQRPolicy > & robotoc::UnconstrOCPSolver::getLQRPolicy | ( | ) | const |
Gets of the local LQR policies over the horizon.
| const SplitSolution & robotoc::UnconstrOCPSolver::getSolution | ( | const int | stage | ) | const |
Get the split solution of a time stage. For example, the control input torques at the initial stage can be obtained by ocp.getSolution(0).u.
| [in] | stage | Time stage of interest. Must be larger than 0 and smaller than N. |
| std::vector< Eigen::VectorXd > robotoc::UnconstrOCPSolver::getSolution | ( | const std::string & | name | ) | const |
Get the solution vector over the horizon.
| [in] | name | Name of the variable. |
| const SolverStatistics & robotoc::UnconstrOCPSolver::getSolverStatistics | ( | ) | const |
Gets the solver statistics.
| const std::vector< GridInfo > & robotoc::UnconstrOCPSolver::getTimeDiscretization | ( | ) | const |
Gets the discretization.
| void robotoc::UnconstrOCPSolver::initConstraints | ( | ) |
Initializes the priaml-dual interior point method for inequality constraints.
| double robotoc::UnconstrOCPSolver::KKTError | ( | ) | const |
Returns the l2-norm of the KKT residuals using the results of UnconstrOCPsolver::updateSolution() or UnconstrOCPsolver::solve().
| double robotoc::UnconstrOCPSolver::KKTError | ( | const double | t, |
| const Eigen::VectorXd & | q, | ||
| const Eigen::VectorXd & | v | ||
| ) |
Computes the KKT residual of the optimal control problem and returns the KKT error, that is, the l2-norm of the KKT residual.
| [in] | t | Initial time of the horizon. |
| [in] | q | Initial configuration. Size must be Robot::dimq(). |
| [in] | v | Initial velocity. Size must be Robot::dimv(). |
|
default |
Default copy assign operator.
|
defaultnoexcept |
Default move assign operator.
| void robotoc::UnconstrOCPSolver::setRobotProperties | ( | const RobotProperties & | properties | ) |
Sets a collection of the properties for robot model in this solver.
| [in] | properties | A collection of the properties for the robot model. |
| void robotoc::UnconstrOCPSolver::setSolution | ( | const std::string & | name, |
| const Eigen::VectorXd & | value | ||
| ) |
Sets the solution over the horizon.
| [in] | name | Name of the variable. |
| [in] | value | Value of the specified variable. |
| void robotoc::UnconstrOCPSolver::setSolverOptions | ( | const SolverOptions & | solver_options | ) |
Sets the solver option.
| [in] | solver_options | Solver options. |
| void robotoc::UnconstrOCPSolver::solve | ( | const double | t, |
| const Eigen::VectorXd & | q, | ||
| const Eigen::VectorXd & | v, | ||
| const bool | init_solver = true |
||
| ) |
Solves the optimal control problem. Internally calls updateSolution().
| [in] | t | Initial time of the horizon. |
| [in] | q | Initial configuration. Size must be Robot::dimq(). |
| [in] | v | Initial velocity. Size must be Robot::dimv(). |
| [in] | init_solver | If true, initializes the solver, that is, calls initConstraints() and clears the line search filter. Default is true. |