robotoc
robotoc - efficient ROBOT Optimal Control solvers
|
MPC solver for the pace gait of quadrupeds. More...
#include <mpc_pace.hpp>
Public Member Functions | |
MPCPace (const Robot &quadruped_robot, const double T, const int N) | |
Construct MPC solver. More... | |
MPCPace () | |
Default constructor. More... | |
~MPCPace () | |
Destructor. More... | |
MPCPace (const MPCPace &)=default | |
Default copy constructor. More... | |
MPCPace & | operator= (const MPCPace &)=default |
Default copy assign operator. More... | |
MPCPace (MPCPace &&) noexcept=default | |
Default move constructor. More... | |
MPCPace & | operator= (MPCPace &&) noexcept=default |
Default move assign operator. More... | |
void | setGaitPattern (const std::shared_ptr< ContactPlannerBase > &foot_step_planner, const double swing_height, const double swing_time, const double stance_time, const double swing_start_time) |
Sets the gait pattern. More... | |
void | init (const double t, const Eigen::VectorXd &q, const Eigen::VectorXd &v, const SolverOptions &solver_options) |
Initializes the optimal control problem solover. More... | |
void | reset () |
Resets the optimal control problem solover via the solution computed by init(). 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 | 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. 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. MPCPace::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< ConfigurationSpaceCost > | getBaseRotationCostHandle () |
Gets the base rotation cost handle. More... | |
std::vector< std::shared_ptr< TaskSpace3DCost > > | getSwingFootCostHandle () |
Gets the swing foot task space costs (LF, LH, RF, RH feet) handle. More... | |
std::shared_ptr< CoMCost > | getCoMCostHandle () |
Gets the com 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... | |
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 pace gait of quadrupeds.
robotoc::MPCPace::MPCPace | ( | const Robot & | quadruped_robot, |
const double | T, | ||
const int | N | ||
) |
Construct MPC solver.
[in] | quadruped_robot | Quadruped robot model. |
[in] | T | Length of the horizon. |
[in] | N | Number of the discretization grids of the horizon. |
robotoc::MPCPace::MPCPace | ( | ) |
Default constructor.
robotoc::MPCPace::~MPCPace | ( | ) |
Destructor.
|
default |
Default copy constructor.
|
defaultnoexcept |
Default move constructor.
std::shared_ptr< ConfigurationSpaceCost > robotoc::MPCPace::getBaseRotationCostHandle | ( | ) |
Gets the base rotation cost handle.
std::shared_ptr< CoMCost > robotoc::MPCPace::getCoMCostHandle | ( | ) |
Gets the com cost handle.
std::shared_ptr< ConfigurationSpaceCost > robotoc::MPCPace::getConfigCostHandle | ( | ) |
Gets the configuration space cost handle.
std::shared_ptr< Constraints > robotoc::MPCPace::getConstraintsHandle | ( | ) |
Gets the constraints handle.
|
inline |
Gets the const handle of the contact sequence.
|
inline |
Gets the control policy at the specified time.
[in] | t | The specified time. |
std::shared_ptr< CostFunction > robotoc::MPCPace::getCostHandle | ( | ) |
Gets the cost function handle.
std::shared_ptr< FrictionCone > robotoc::MPCPace::getFrictionConeHandle | ( | ) |
Gets the friction cone constraints handle.
const Eigen::VectorXd & robotoc::MPCPace::getInitialControlInput | ( | ) | const |
Get the initial control input.
const aligned_vector< LQRPolicy > & robotoc::MPCPace::getLQRPolicy | ( | ) | const |
Gets of the local LQR policies over the horizon.
const Solution & robotoc::MPCPace::getSolution | ( | ) | const |
Get the solution.
|
inline |
Gets the const handle of the MPC solver.
std::vector< std::shared_ptr< TaskSpace3DCost > > robotoc::MPCPace::getSwingFootCostHandle | ( | ) |
Gets the swing foot task space costs (LF, LH, RF, RH feet) handle.
void robotoc::MPCPace::init | ( | const double | t, |
const Eigen::VectorXd & | q, | ||
const Eigen::VectorXd & | v, | ||
const SolverOptions & | solver_options | ||
) |
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. |
double robotoc::MPCPace::KKTError | ( | ) | const |
Returns the l2-norm of the KKT residuals. MPCPace::updateSolution() must be computed.
double robotoc::MPCPace::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::MPCPace::reset | ( | ) |
Resets the optimal control problem solover via the solution computed by init().
void robotoc::MPCPace::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::MPCPace::setGaitPattern | ( | const std::shared_ptr< ContactPlannerBase > & | foot_step_planner, |
const double | swing_height, | ||
const double | swing_time, | ||
const double | stance_time, | ||
const double | swing_start_time | ||
) |
Sets the gait pattern.
[in] | foot_step_planner | Foot step planner of the gait. |
[in] | swing_height | Swing height of the gait. |
[in] | swing_time | Swing time of the gait. |
[in] | stance_time | Stance time of the gait. |
[in] | swing_start_time | Start time of the gait. |
void robotoc::MPCPace::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::MPCPace::setSolverOptions | ( | const SolverOptions & | solver_options | ) |
Sets the solver options.
[in] | solver_options | Solver options. |
void robotoc::MPCPace::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(). |