centroidal_control_collection
Classes | Public Types | Public Member Functions | Public Attributes | Static Public Attributes | Protected Member Functions | List of all members
CCC::LinearMpcXY Class Reference

Linear MPC of translational and rotational x,y-component motion considering predefined z-component motion. More...

#include <LinearMpcXY.h>

Collaboration diagram for CCC::LinearMpcXY:
Collaboration graph
[legend]

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 &current_x, const Eigen::VectorXd &ref_output_seq)
 Process one step. More...
 

Detailed Description

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.

Member Typedef Documentation

◆ _StateSpaceModel

using CCC::LinearMpcXY::_StateSpaceModel = StateSpaceModel<state_dim_, Eigen::Dynamic, Eigen::Dynamic>

Type of state-space model.

Definition at line 35 of file LinearMpcXY.h.

◆ StateDimVector

Type of state vector.

Definition at line 38 of file LinearMpcXY.h.

Constructor & Destructor Documentation

◆ LinearMpcXY()

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.

Parameters
massrobot mass [kg]
horizon_dtdiscretization timestep in horizon [sec]
horizon_stepsnumber of steps in horizon
weight_paramobjective weight parameter
qp_solver_typeQP solver type

Member Function Documentation

◆ planOnce()

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.

Parameters
motion_param_funcfunction of motion parameter
ref_data_funcfunction of reference data
initial_paraminitial parameter
current_timecurrent time (i.e., start time of horizon) [sec]
Returns
planned force scales

◆ procOnce()

Eigen::VectorXd CCC::LinearMpcXY::procOnce ( const std::vector< std::shared_ptr< _StateSpaceModel >> &  model_list,
const StateDimVector current_x,
const Eigen::VectorXd &  ref_output_seq 
)
protected

Process one step.

Member Data Documentation

◆ force_range_

std::pair<double, double> CCC::LinearMpcXY::force_range_

Min/max ridge force [N].

Definition at line 255 of file LinearMpcXY.h.

◆ horizon_dt_

double CCC::LinearMpcXY::horizon_dt_ = 0

Discretization timestep in horizon [sec].

Definition at line 240 of file LinearMpcXY.h.

◆ horizon_steps_

int CCC::LinearMpcXY::horizon_steps_ = 0

Number of steps in horizon.

Definition at line 243 of file LinearMpcXY.h.

◆ mass_

double CCC::LinearMpcXY::mass_ = 0

Robot mass [kg].

Definition at line 237 of file LinearMpcXY.h.

◆ qp_coeff_

QpSolverCollection::QpCoeff CCC::LinearMpcXY::qp_coeff_

QP coefficients.

Definition at line 252 of file LinearMpcXY.h.

◆ qp_solver_

std::shared_ptr<QpSolverCollection::QpSolver> CCC::LinearMpcXY::qp_solver_

QP solver.

Definition at line 249 of file LinearMpcXY.h.

◆ state_dim_

constexpr int CCC::LinearMpcXY::state_dim_ = 6
staticconstexpr

State dimension.

Definition at line 32 of file LinearMpcXY.h.

◆ weight_param_

WeightParam CCC::LinearMpcXY::weight_param_

Objective weight parameter.

Definition at line 246 of file LinearMpcXY.h.


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