sobec::MPCWalk Class Reference

#include <sobec/walk-without-think/mpc.hpp>

Public Member Functions

EIGEN_MAKE_ALIGNED_OPERATOR_NEW MPCWalk (boost::shared_ptr< MPCWalkParams > params, boost::shared_ptr< ShootingProblem > problem)
 
virtual ~MPCWalk ()
 
void initialize (const std::vector< Eigen::VectorXd > &xs, const std::vector< Eigen::VectorXd > &us)
 once all fields are set, init the mpc manager with guess traj More...
 
void calc (const Eigen::Ref< const VectorXd > &x, const int t)
 calc the OCP solution. Init must be called first. More...
 
void updateTerminalCost (const int t)
 
void findTerminalStateResidualModel ()
 
void findStateModel ()
 

Public Attributes

boost::shared_ptr< MPCWalkParamsparams
 Parameters to tune the algorithm, given at init. More...
 
boost::shared_ptr< ShootingProblem > storage
 The reference shooting problem storing all shooting nodes. More...
 
boost::shared_ptr< ShootingProblem > problem
 the MPC problem used for solving. More...
 
boost::shared_ptr< SolverFDDP > solver
 Solver for MPC. More...
 
boost::shared_ptr< ResidualModelState > terminalStateResidual
 Keep a direct reference to the terminal residual. More...
 
boost::shared_ptr< StateMultibody > state
 Keep a direct reference to the terminal state. More...
 

Protected Attributes

double reg
 

Constructor & Destructor Documentation

◆ MPCWalk()

sobec::MPCWalk::MPCWalk ( boost::shared_ptr< MPCWalkParams params,
boost::shared_ptr< ShootingProblem >  problem 
)
explicit

◆ ~MPCWalk()

virtual sobec::MPCWalk::~MPCWalk ( )
inlinevirtual

Member Function Documentation

◆ calc()

void sobec::MPCWalk::calc ( const Eigen::Ref< const VectorXd > &  x,
const int  t 
)

calc the OCP solution. Init must be called first.

Change the value of the reference cost

Recede the horizon

Change Warm start

Change init constraint

Solve

◆ findStateModel()

void sobec::MPCWalk::findStateModel ( )

◆ findTerminalStateResidualModel()

void sobec::MPCWalk::findTerminalStateResidualModel ( )

◆ initialize()

void sobec::MPCWalk::initialize ( const std::vector< Eigen::VectorXd > &  xs,
const std::vector< Eigen::VectorXd > &  us 
)

once all fields are set, init the mpc manager with guess traj

◆ updateTerminalCost()

void sobec::MPCWalk::updateTerminalCost ( const int  t)

Member Data Documentation

◆ params

boost::shared_ptr<MPCWalkParams> sobec::MPCWalk::params

Parameters to tune the algorithm, given at init.

◆ problem

boost::shared_ptr<ShootingProblem> sobec::MPCWalk::problem

the MPC problem used for solving.

◆ reg

double sobec::MPCWalk::reg
protected

◆ solver

boost::shared_ptr<SolverFDDP> sobec::MPCWalk::solver

Solver for MPC.

◆ state

boost::shared_ptr<StateMultibody> sobec::MPCWalk::state

Keep a direct reference to the terminal state.

◆ storage

boost::shared_ptr<ShootingProblem> sobec::MPCWalk::storage

The reference shooting problem storing all shooting nodes.

◆ terminalStateResidual

boost::shared_ptr<ResidualModelState> sobec::MPCWalk::terminalStateResidual

Keep a direct reference to the terminal residual.


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