robotoc
robotoc - efficient ROBOT Optimal Control solvers
Loading...
Searching...
No Matches
robotoc::MPCPace Class Reference

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...
 
MPCPaceoperator= (const MPCPace &)=default
 Default copy assign operator. More...
 
 MPCPace (MPCPace &&) noexcept=default
 Default move constructor. More...
 
MPCPaceoperator= (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 SolutiongetSolution () 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< CostFunctiongetCostHandle ()
 Gets the cost function handle.
More...
 
std::shared_ptr< ConfigurationSpaceCostgetConfigCostHandle ()
 Gets the configuration space cost handle.
More...
 
std::shared_ptr< ConfigurationSpaceCostgetBaseRotationCostHandle ()
 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< CoMCostgetCoMCostHandle ()
 Gets the com cost handle.
More...
 
std::shared_ptr< ConstraintsgetConstraintsHandle ()
 Gets the constraints handle.
More...
 
std::shared_ptr< FrictionConegetFrictionConeHandle ()
 Gets the friction cone constraints handle.
More...
 
const OCPSolvergetSolver () 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...
 

Detailed Description

MPC solver for the pace gait of quadrupeds.

Constructor & Destructor Documentation

◆ MPCPace() [1/4]

robotoc::MPCPace::MPCPace ( const Robot quadruped_robot,
const double  T,
const int  N 
)

Construct MPC solver.

Parameters
[in]quadruped_robotQuadruped robot model.
[in]TLength of the horizon.
[in]NNumber of the discretization grids of the horizon.

◆ MPCPace() [2/4]

robotoc::MPCPace::MPCPace ( )

Default constructor.

◆ ~MPCPace()

robotoc::MPCPace::~MPCPace ( )

Destructor.

◆ MPCPace() [3/4]

robotoc::MPCPace::MPCPace ( const MPCPace )
default

Default copy constructor.

◆ MPCPace() [4/4]

robotoc::MPCPace::MPCPace ( MPCPace &&  )
defaultnoexcept

Default move constructor.

Member Function Documentation

◆ getBaseRotationCostHandle()

std::shared_ptr< ConfigurationSpaceCost > robotoc::MPCPace::getBaseRotationCostHandle ( )

Gets the base rotation cost handle.

Returns
Shared ptr to the base rotation cost.

◆ getCoMCostHandle()

std::shared_ptr< CoMCost > robotoc::MPCPace::getCoMCostHandle ( )

Gets the com cost handle.

Returns
Shared ptr to the com cost.

◆ getConfigCostHandle()

std::shared_ptr< ConfigurationSpaceCost > robotoc::MPCPace::getConfigCostHandle ( )

Gets the configuration space cost handle.

Returns
Shared ptr to the configuration space cost.

◆ getConstraintsHandle()

std::shared_ptr< Constraints > robotoc::MPCPace::getConstraintsHandle ( )

Gets the constraints handle.

Returns
Shared ptr to the constraints.

◆ getContactSequence()

const std::shared_ptr< ContactSequence > & robotoc::MPCPace::getContactSequence ( ) const
inline

Gets the const handle of the contact sequence.

Returns
Const reference to the shared_ptr of the contact sequence.

◆ getControlPolicy()

ControlPolicy robotoc::MPCPace::getControlPolicy ( const double  t) const
inline

Gets the control policy at the specified time.

Parameters
[in]tThe specified time.
Returns
Control poclity at the specified time.

◆ getCostHandle()

std::shared_ptr< CostFunction > robotoc::MPCPace::getCostHandle ( )

Gets the cost function handle.

Returns
Shared ptr to the cost function.

◆ getFrictionConeHandle()

std::shared_ptr< FrictionCone > robotoc::MPCPace::getFrictionConeHandle ( )

Gets the friction cone constraints handle.

Returns
Shared ptr to the friction cone constraints.

◆ getInitialControlInput()

const Eigen::VectorXd & robotoc::MPCPace::getInitialControlInput ( ) const

Get the initial control input.

Returns
Const reference to the control input.

◆ getLQRPolicy()

const aligned_vector< LQRPolicy > & robotoc::MPCPace::getLQRPolicy ( ) const

Gets of the local LQR policies over the horizon.

Returns
const reference to the local LQR policies.

◆ getSolution()

const Solution & robotoc::MPCPace::getSolution ( ) const

Get the solution.

Returns
const reference to the solution.

◆ getSolver()

const OCPSolver & robotoc::MPCPace::getSolver ( ) const
inline

Gets the const handle of the MPC solver.

Returns
Const reference to the MPC solver.

◆ getSwingFootCostHandle()

std::vector< std::shared_ptr< TaskSpace3DCost > > robotoc::MPCPace::getSwingFootCostHandle ( )

Gets the swing foot task space costs (LF, LH, RF, RH feet) handle.

Returns
Shared ptr to the task space cost (LF, LH, RF, RH feet).

◆ init()

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.

Parameters
[in]tInitial time of the horizon.
[in]qInitial configuration. Size must be Robot::dimq().
[in]vInitial velocity. Size must be Robot::dimv().
[in]solver_optionsSolver options for the initialization.
Remarks
The linear and angular velocities of the floating base are assumed to be expressed in the body local coordinate.

◆ KKTError() [1/2]

double robotoc::MPCPace::KKTError ( ) const

Returns the l2-norm of the KKT residuals. MPCPace::updateSolution() must be computed.

Returns
The l2-norm of the KKT residual.

◆ KKTError() [2/2]

double robotoc::MPCPace::KKTError ( const double  t,
const Eigen::VectorXd &  q,
const Eigen::VectorXd &  v 
)

Computes the KKT residual of the optimal control problem.

Parameters
[in]tInitial time of the horizon.
[in]qInitial configuration. Size must be Robot::dimq().
[in]vInitial velocity. Size must be Robot::dimv().
Remarks
The linear and angular velocities of the floating base are assumed to be expressed in the body local coordinate.

◆ operator=() [1/2]

MPCPace & robotoc::MPCPace::operator= ( const MPCPace )
default

Default copy assign operator.

◆ operator=() [2/2]

MPCPace & robotoc::MPCPace::operator= ( MPCPace &&  )
defaultnoexcept

Default move assign operator.

◆ reset() [1/2]

void robotoc::MPCPace::reset ( )

Resets the optimal control problem solover via the solution computed by init().

◆ reset() [2/2]

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.

◆ setGaitPattern()

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.

Parameters
[in]foot_step_plannerFoot step planner of the gait.
[in]swing_heightSwing height of the gait.
[in]swing_timeSwing time of the gait.
[in]stance_timeStance time of the gait.
[in]swing_start_timeStart time of the gait.

◆ setRobotProperties()

void robotoc::MPCPace::setRobotProperties ( const RobotProperties properties)

Sets a collection of the properties for robot model in this MPC.

Parameters
[in]propertiesA collection of the properties for the robot model.

◆ setSolverOptions()

void robotoc::MPCPace::setSolverOptions ( const SolverOptions solver_options)

Sets the solver options.

Parameters
[in]solver_optionsSolver options.

◆ updateSolution()

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.

Parameters
[in]tInitial time of the horizon.
[in]dtSampling time of MPC. Must be positive.
[in]qConfiguration. Size must be Robot::dimq().
[in]vVelocity. Size must be Robot::dimv().
Remarks
The linear and angular velocities of the floating base are assumed to be expressed in the body local coordinate.

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