|
centroidal_control_collection
|
Linear MPC of translational and rotational x,y-component motion considering predefined z-component motion. More...
#include <LinearMpcXY.h>

Classes | |
| struct | InitialParam |
| Initial parameter. More... | |
| class | Model |
| State-space model. More... | |
| struct | MotionParam |
| Motion parameter. More... | |
| struct | RefData |
| Reference data. More... | |
| struct | WeightParam |
| Weight parameter. More... | |
Public Types | |
| using | _StateSpaceModel = StateSpaceModel< state_dim_, Eigen::Dynamic, Eigen::Dynamic > |
| Type of state-space model. More... | |
| using | StateDimVector = _StateSpaceModel::StateDimVector |
| Type of state vector. More... | |
Public Member Functions | |
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW | LinearMpcXY (double mass, double horizon_dt, int horizon_steps, const WeightParam &weight_param=WeightParam(), QpSolverCollection::QpSolverType qp_solver_type=QpSolverCollection::QpSolverType::Any) |
| Constructor. More... | |
| Eigen::VectorXd | planOnce (const std::function< MotionParam(double)> &motion_param_func, const std::function< RefData(double)> &ref_data_func, const InitialParam &initial_param, double current_time) |
| Plan one step. More... | |
Public Attributes | |
| double | mass_ = 0 |
| Robot mass [kg]. More... | |
| double | horizon_dt_ = 0 |
| Discretization timestep in horizon [sec]. More... | |
| int | horizon_steps_ = 0 |
| Number of steps in horizon. More... | |
| WeightParam | weight_param_ |
| Objective weight parameter. More... | |
| std::shared_ptr< QpSolverCollection::QpSolver > | qp_solver_ |
| QP solver. More... | |
| QpSolverCollection::QpCoeff | qp_coeff_ |
| QP coefficients. More... | |
| std::pair< double, double > | force_range_ |
| Min/max ridge force [N]. More... | |
Static Public Attributes | |
| static constexpr int | state_dim_ = 6 |
| State dimension. More... | |
Protected Member Functions | |
| Eigen::VectorXd | procOnce (const std::vector< std::shared_ptr< _StateSpaceModel >> &model_list, const StateDimVector ¤t_x, const Eigen::VectorXd &ref_output_seq) |
| Process one step. More... | |
Linear MPC of translational and rotational x,y-component motion considering predefined z-component motion.
See the following for a detailed formulation.
Definition at line 28 of file LinearMpcXY.h.
| using CCC::LinearMpcXY::_StateSpaceModel = StateSpaceModel<state_dim_, Eigen::Dynamic, Eigen::Dynamic> |
Type of state-space model.
Definition at line 35 of file LinearMpcXY.h.
Type of state vector.
Definition at line 38 of file LinearMpcXY.h.
| EIGEN_MAKE_ALIGNED_OPERATOR_NEW CCC::LinearMpcXY::LinearMpcXY | ( | double | mass, |
| double | horizon_dt, | ||
| int | horizon_steps, | ||
| const WeightParam & | weight_param = WeightParam(), |
||
| QpSolverCollection::QpSolverType | qp_solver_type = QpSolverCollection::QpSolverType::Any |
||
| ) |
Constructor.
| mass | robot mass [kg] |
| horizon_dt | discretization timestep in horizon [sec] |
| horizon_steps | number of steps in horizon |
| weight_param | objective weight parameter |
| qp_solver_type | QP solver type |
| Eigen::VectorXd CCC::LinearMpcXY::planOnce | ( | const std::function< MotionParam(double)> & | motion_param_func, |
| const std::function< RefData(double)> & | ref_data_func, | ||
| const InitialParam & | initial_param, | ||
| double | current_time | ||
| ) |
Plan one step.
| motion_param_func | function of motion parameter |
| ref_data_func | function of reference data |
| initial_param | initial parameter |
| current_time | current time (i.e., start time of horizon) [sec] |
|
protected |
Process one step.
| std::pair<double, double> CCC::LinearMpcXY::force_range_ |
Min/max ridge force [N].
Definition at line 255 of file LinearMpcXY.h.
| double CCC::LinearMpcXY::horizon_dt_ = 0 |
Discretization timestep in horizon [sec].
Definition at line 240 of file LinearMpcXY.h.
| int CCC::LinearMpcXY::horizon_steps_ = 0 |
Number of steps in horizon.
Definition at line 243 of file LinearMpcXY.h.
| double CCC::LinearMpcXY::mass_ = 0 |
Robot mass [kg].
Definition at line 237 of file LinearMpcXY.h.
| QpSolverCollection::QpCoeff CCC::LinearMpcXY::qp_coeff_ |
QP coefficients.
Definition at line 252 of file LinearMpcXY.h.
| std::shared_ptr<QpSolverCollection::QpSolver> CCC::LinearMpcXY::qp_solver_ |
QP solver.
Definition at line 249 of file LinearMpcXY.h.
|
staticconstexpr |
State dimension.
Definition at line 32 of file LinearMpcXY.h.
| WeightParam CCC::LinearMpcXY::weight_param_ |
Objective weight parameter.
Definition at line 246 of file LinearMpcXY.h.