| 
    robotoc
    
   robotoc - efficient ROBOT Optimal Control solvers 
   | 
 
MPC solver for the jump control. More...
#include <mpc_jump.hpp>
Public Member Functions | |
| MPCJump (const Robot &robot, const double T, const int N) | |
| Construct MPC solver.  More... | |
| MPCJump () | |
| Default constructor.  More... | |
| ~MPCJump () | |
| Destructor.  More... | |
| MPCJump (const MPCJump &)=default | |
| Default copy constructor.  More... | |
| MPCJump & | operator= (const MPCJump &)=default | 
| Default copy assign operator.  More... | |
| MPCJump (MPCJump &&) noexcept=default | |
| Default move constructor.  More... | |
| MPCJump & | operator= (MPCJump &&) noexcept=default | 
| Default move assign operator.  More... | |
| void | setJumpPattern (const std::shared_ptr< ContactPlannerBase > &foot_step_planner, const double flying_time, const double min_flying_time, const double ground_time, const double min_ground_time) | 
| Sets the gait pattern.  More... | |
| void | init (const double t, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const SolverOptions &solver_options, const bool sto=false) | 
| Initializes the optimal control problem solover.  More... | |
| void | reset () | 
| Resets the optimal control problem solover via the solution computed by init() or reset().  More... | |
| void | reset (const Eigen::VectorXd &q, const Eigen::VectorXd &v) | 
| Resets the optimal control problem solover via the solution computed by init(), q, and v.  More... | |
| void | reset (const double t, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const SolverOptions &solver_options, const bool sto=false) | 
| Resets the optimal control problem solver using the previous results of init() or reset().  More... | |
| void | setSolverOptions (const SolverOptions &solver_options) | 
| Sets the solver options.  More... | |
| void | updateSolution (const double t, const double dt, const Eigen::VectorXd &q, const Eigen::VectorXd &v) | 
| Updates the solution by iterationg the Newton-type method.  More... | |
| const Eigen::VectorXd & | getInitialControlInput () const | 
| Get the initial control input.  More... | |
| const Solution & | getSolution () const | 
| Get the solution over the horizon.  More... | |
| const aligned_vector< LQRPolicy > & | getLQRPolicy () const | 
| Gets of the local LQR policies over the horizon.  More... | |
| ControlPolicy | getControlPolicy (const double t) const | 
| Gets the control policy at the specified time.  More...  | |
| double | KKTError (const double t, const Eigen::VectorXd &q, const Eigen::VectorXd &v) | 
| Computes the KKT residual of the optimal control problem.  More... | |
| double | KKTError () const | 
| Returns the l2-norm of the KKT residuals. MPCJump::updateSolution() must be computed.  More...  | |
| std::shared_ptr< CostFunction > | getCostHandle () | 
| Gets the cost function handle.  More...  | |
| std::shared_ptr< ConfigurationSpaceCost > | getConfigCostHandle () | 
| Gets the configuration space cost handle.  More...  | |
| std::shared_ptr< Constraints > | getConstraintsHandle () | 
| Gets the constraints handle.  More...  | |
| std::shared_ptr< FrictionCone > | getFrictionConeHandle () | 
| Gets the friction cone constraints handle.  More...  | |
| std::shared_ptr< ContactWrenchCone > | getContactWrenchConeHandle () | 
| Gets the contact wrench cone constraints handle.  More...  | |
| const OCPSolver & | getSolver () const | 
| Gets the const handle of the MPC solver.  More...  | |
| const std::shared_ptr< ContactSequence > & | getContactSequence () const | 
| Gets the const handle of the contact sequence.  More...  | |
| void | setRobotProperties (const RobotProperties &properties) | 
| Sets a collection of the properties for robot model in this MPC.  More... | |
MPC solver for the jump control.
| robotoc::MPCJump::MPCJump | ( | const Robot & | robot, | 
| const double | T, | ||
| const int | N | ||
| ) | 
Construct MPC solver.
| [in] | robot | Robot model. | 
| [in] | T | Length of the horizon. | 
| [in] | N | Number of the discretization grids of the horizon. | 
| robotoc::MPCJump::MPCJump | ( | ) | 
Default constructor.
| robotoc::MPCJump::~MPCJump | ( | ) | 
Destructor.
      
  | 
  default | 
Default copy constructor.
      
  | 
  defaultnoexcept | 
Default move constructor.
| std::shared_ptr< ConfigurationSpaceCost > robotoc::MPCJump::getConfigCostHandle | ( | ) | 
Gets the configuration space cost handle. 
 
| std::shared_ptr< Constraints > robotoc::MPCJump::getConstraintsHandle | ( | ) | 
Gets the constraints handle. 
 
      
  | 
  inline | 
Gets the const handle of the contact sequence. 
 
| std::shared_ptr< ContactWrenchCone > robotoc::MPCJump::getContactWrenchConeHandle | ( | ) | 
Gets the contact wrench cone constraints handle. 
 
      
  | 
  inline | 
Gets the control policy at the specified time. 
 
| [in] | t | The specified time.  | 
| std::shared_ptr< CostFunction > robotoc::MPCJump::getCostHandle | ( | ) | 
Gets the cost function handle. 
 
| std::shared_ptr< FrictionCone > robotoc::MPCJump::getFrictionConeHandle | ( | ) | 
Gets the friction cone constraints handle. 
 
| const Eigen::VectorXd & robotoc::MPCJump::getInitialControlInput | ( | ) | const | 
Get the initial control input.
| const aligned_vector< LQRPolicy > & robotoc::MPCJump::getLQRPolicy | ( | ) | const | 
Gets of the local LQR policies over the horizon.
| const Solution & robotoc::MPCJump::getSolution | ( | ) | const | 
Get the solution over the horizon.
      
  | 
  inline | 
Gets the const handle of the MPC solver. 
 
| void robotoc::MPCJump::init | ( | const double | t, | 
| const Eigen::VectorXd & | q, | ||
| const Eigen::VectorXd & | v, | ||
| const SolverOptions & | solver_options, | ||
| const bool | sto = false  | 
        ||
| ) | 
Initializes the optimal control problem solover.
| [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] | solver_options | Solver options for the initialization. | 
| [in] | sto | If true, the STO algorithm is enabled, that is, the lift-off and touch-down timings are optimized. | 
| double robotoc::MPCJump::KKTError | ( | ) | const | 
Returns the l2-norm of the KKT residuals. MPCJump::updateSolution() must be computed. 
 
| double robotoc::MPCJump::KKTError | ( | const double | t, | 
| const Eigen::VectorXd & | q, | ||
| const Eigen::VectorXd & | v | ||
| ) | 
Computes the KKT residual of the optimal control problem.
| [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(). | 
| void robotoc::MPCJump::reset | ( | ) | 
| void robotoc::MPCJump::reset | ( | const double | t, | 
| const Eigen::VectorXd & | q, | ||
| const Eigen::VectorXd & | v, | ||
| const SolverOptions & | solver_options, | ||
| const bool | sto = false  | 
        ||
| ) | 
Resets the optimal control problem solver using the previous results of init() or reset().
| [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] | solver_options | Solver options for the initialization. | 
| [in] | sto | If true, lift-off and touch-down timings are optimized. | 
| void robotoc::MPCJump::reset | ( | const Eigen::VectorXd & | q, | 
| const Eigen::VectorXd & | v | ||
| ) | 
Resets the optimal control problem solover via the solution computed by init(), q, and v.
| void robotoc::MPCJump::setJumpPattern | ( | const std::shared_ptr< ContactPlannerBase > & | foot_step_planner, | 
| const double | flying_time, | ||
| const double | min_flying_time, | ||
| const double | ground_time, | ||
| const double | min_ground_time | ||
| ) | 
Sets the gait pattern.
| [in] | foot_step_planner | Foot step planner of the jump. | 
| [in] | flying_time | If STO is enabled, this is initial guess of the flying time. Otherwise, this is used as the fixed flying time. | 
| [in] | min_flying_time | Minimum flying time. | 
| [in] | ground_time | If STO is enabled, this is initial guess of the ground time. Otherwise, this is used as the fixed ground time. | 
| [in] | min_ground_time | Minimum time duration after landing. | 
| void robotoc::MPCJump::setRobotProperties | ( | const RobotProperties & | properties | ) | 
Sets a collection of the properties for robot model in this MPC.
| [in] | properties | A collection of the properties for the robot model. | 
| void robotoc::MPCJump::setSolverOptions | ( | const SolverOptions & | solver_options | ) | 
Sets the solver options.
| [in] | solver_options | Solver options.  | 
| void robotoc::MPCJump::updateSolution | ( | const double | t, | 
| const double | dt, | ||
| const Eigen::VectorXd & | q, | ||
| const Eigen::VectorXd & | v | ||
| ) | 
Updates the solution by iterationg the Newton-type method.
| [in] | t | Initial time of the horizon. | 
| [in] | dt | Sampling time of MPC. Must be positive. | 
| [in] | q | Configuration. Size must be Robot::dimq(). | 
| [in] | v | Velocity. Size must be Robot::dimv(). |