centroidal_control_collection
|
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... | |
Preview control for centroidal model.
See the following for a detailed formulation.
Definition at line 137 of file PreviewControlCentroidal.h.
CCC::PreviewControlCentroidal::PreviewControlCentroidal | ( | double | mass, |
const Eigen::Vector3d & | moment_of_inertia, | ||
double | horizon_duration, | ||
double | horizon_dt, | ||
const WeightParam & | weight_param = WeightParam() |
||
) |
Constructor.
mass | mass [kg] |
moment_of_inertia | moment of inertia [kg m^2] |
horizon_duration | horizon duration [sec] |
horizon_dt | discretization timestep in horizon [sec] |
weight_param | objective weight parameter |
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.
motion_param | motion parameter |
ref_data_func | function of reference data |
initial_param | initial parameter |
current_time | current time (i.e., start time of horizon) [sec] |
control_dt | control timestep used to calculate the planned wrench (if omitted, horizon_dt is used) |
|
protected |
Mass [kg].
Definition at line 261 of file PreviewControlCentroidal.h.
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.
mc_rtc::Configuration CCC::PreviewControlCentroidal::wrench_dist_config_ |
Configuration of wrench distribution.
Definition at line 257 of file PreviewControlCentroidal.h.