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

Preview control for centroidal model. More...

#include <PreviewControlCentroidal.h>

Classes

struct  InitialParam
 Initial parameter. More...
 
struct  MotionParam
 Motion parameter. More...
 
struct  RefData
 Reference data. More...
 
struct  WeightParam
 Weight parameter. More...
 

Public Member Functions

 PreviewControlCentroidal (double mass, const Eigen::Vector3d &moment_of_inertia, double horizon_duration, double horizon_dt, const WeightParam &weight_param=WeightParam())
 Constructor. More...
 
sva::ForceVecd planOnce (const MotionParam &motion_param, const std::function< RefData(double)> &ref_data_func, const InitialParam &initial_param, double current_time, double control_dt=-1) const
 Plan one step. More...
 

Public Attributes

std::array< std::shared_ptr< PreviewControlCentroidal1d >, 6 > preview_control_1d_
 List of one-dimensional preview control. More...
 
mc_rtc::Configuration wrench_dist_config_
 Configuration of wrench distribution. More...
 

Protected Attributes

double mass_
 Mass [kg]. More...
 

Detailed Description

Preview control for centroidal model.

See the following for a detailed formulation.

Definition at line 137 of file PreviewControlCentroidal.h.

Constructor & Destructor Documentation

◆ PreviewControlCentroidal()

CCC::PreviewControlCentroidal::PreviewControlCentroidal ( double  mass,
const Eigen::Vector3d &  moment_of_inertia,
double  horizon_duration,
double  horizon_dt,
const WeightParam weight_param = WeightParam() 
)

Constructor.

Parameters
massmass [kg]
moment_of_inertiamoment of inertia [kg m^2]
horizon_durationhorizon duration [sec]
horizon_dtdiscretization timestep in horizon [sec]
weight_paramobjective weight parameter

Member Function Documentation

◆ planOnce()

sva::ForceVecd CCC::PreviewControlCentroidal::planOnce ( const MotionParam motion_param,
const std::function< RefData(double)> &  ref_data_func,
const InitialParam initial_param,
double  current_time,
double  control_dt = -1 
) const

Plan one step.

Parameters
motion_parammotion parameter
ref_data_funcfunction of reference data
initial_paraminitial parameter
current_timecurrent time (i.e., start time of horizon) [sec]
control_dtcontrol timestep used to calculate the planned wrench (if omitted, horizon_dt is used)
Returns
planned wrench

Member Data Documentation

◆ mass_

double CCC::PreviewControlCentroidal::mass_
protected

Mass [kg].

Definition at line 261 of file PreviewControlCentroidal.h.

◆ preview_control_1d_

std::array<std::shared_ptr<PreviewControlCentroidal1d>, 6> CCC::PreviewControlCentroidal::preview_control_1d_

List of one-dimensional preview control.

The first three elements are for orientation components and the latter three are for position components.

Definition at line 254 of file PreviewControlCentroidal.h.

◆ wrench_dist_config_

mc_rtc::Configuration CCC::PreviewControlCentroidal::wrench_dist_config_

Configuration of wrench distribution.

Definition at line 257 of file PreviewControlCentroidal.h.


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