#include <sobec/walk-without-think/mpc.hpp>
|
| boost::shared_ptr< MPCWalkParams > | params |
| | 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...
|
| |
◆ MPCWalk()
| sobec::MPCWalk::MPCWalk |
( |
boost::shared_ptr< MPCWalkParams > |
params, |
|
|
boost::shared_ptr< ShootingProblem > |
problem |
|
) |
| |
|
explicit |
◆ ~MPCWalk()
| virtual sobec::MPCWalk::~MPCWalk |
( |
| ) |
|
|
inlinevirtual |
◆ 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 | ) |
|
◆ 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 |
◆ 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:
- include/sobec/walk-without-think/mpc.hpp
- include/sobec/walk-without-think/mpc.hxx