Public Types | Public Member Functions | Public Attributes | List of all members
towr::Parameters Struct Reference

Holds the parameters to tune the optimization problem. More...

#include <parameters.h>

Public Types

using CostWeights = std::vector< std::pair< CostName, double >>
 
using EEID = unsigned int
 
using UsedConstraints = std::vector< ConstraintName >
 
using VecTimes = std::vector< double >
 

Public Member Functions

VecTimes GetBasePolyDurations () const
 The durations of each base polynomial in the spline (lin+ang). More...
 
int GetEECount () const
 The number of endeffectors. More...
 
int GetPhaseCount (EEID ee) const
 The number of phases allowed for endeffector ee. More...
 
bool OptimizeTimings () const
 True if the phase durations should be optimized over. More...
 
 Parameters ()
 Default parameters to use. More...
 
virtual ~Parameters ()=default
 

Public Attributes

UsedConstraints constraints_
 Which constraints should be used in the optimization problem. More...
 
CostWeights costs_
 Which costs should be used in the optimiation problem. More...
 
double dt_constraint_base_motion_
 Interval at which the base motion constraint is enforced. More...
 
double dt_constraint_dynamic_
 Interval at which the dynamic constraint is enforced. More...
 
double dt_constraint_range_of_motion_
 Interval at which the range of motion constraint is enforced. More...
 
double duration_base_polynomial_
 Fixed duration of each cubic polynomial describing the base motion. More...
 
std::vector< bool > ee_in_contact_at_start_
 True if the foot is initially in contact with the terrain. More...
 
std::vector< VecTimesee_phase_durations_
 Number and initial duration of each foot's swing and stance phases. More...
 
int ee_polynomials_per_swing_phase_
 Number of polynomials to parameterize foot movement during swing phases. More...
 
double force_limit_in_norm_
 The maximum allowable force [N] in normal direction. More...
 
int force_polynomials_per_stance_phase_
 Number of polynomials to parameterize each contact force during stance phase. More...
 
double max_phase_duration_
 When optimizing over phase duration, this is is maximum allowed. More...
 
double min_phase_duration_
 When optimizing over phase duration, this is the minimum allowed. More...
 
double t_total_
 Total duration [s] of the walking motion. More...
 

Detailed Description

Holds the parameters to tune the optimization problem.

Definition at line 45 of file parameters.h.

Member Typedef Documentation

using towr::Parameters::CostWeights = std::vector<std::pair<CostName, double>>

Definition at line 47 of file parameters.h.

using towr::Parameters::EEID = unsigned int

Definition at line 50 of file parameters.h.

Definition at line 48 of file parameters.h.

using towr::Parameters::VecTimes = std::vector<double>

Definition at line 49 of file parameters.h.

Constructor & Destructor Documentation

towr::Parameters::Parameters ( )

Default parameters to use.

Definition at line 36 of file parameters.cc.

virtual towr::Parameters::~Parameters ( )
virtualdefault

Member Function Documentation

Parameters::VecTimes towr::Parameters::GetBasePolyDurations ( ) const

The durations of each base polynomial in the spline (lin+ang).

Definition at line 87 of file parameters.cc.

int towr::Parameters::GetEECount ( ) const

The number of endeffectors.

Definition at line 111 of file parameters.cc.

int towr::Parameters::GetPhaseCount ( EEID  ee) const

The number of phases allowed for endeffector ee.

Definition at line 105 of file parameters.cc.

bool towr::Parameters::OptimizeTimings ( ) const

True if the phase durations should be optimized over.

Definition at line 79 of file parameters.cc.

Member Data Documentation

UsedConstraints towr::Parameters::constraints_

Which constraints should be used in the optimization problem.

Definition at line 59 of file parameters.h.

CostWeights towr::Parameters::costs_

Which costs should be used in the optimiation problem.

Definition at line 62 of file parameters.h.

double towr::Parameters::dt_constraint_base_motion_

Interval at which the base motion constraint is enforced.

Definition at line 74 of file parameters.h.

double towr::Parameters::dt_constraint_dynamic_

Interval at which the dynamic constraint is enforced.

Definition at line 68 of file parameters.h.

double towr::Parameters::dt_constraint_range_of_motion_

Interval at which the range of motion constraint is enforced.

Definition at line 71 of file parameters.h.

double towr::Parameters::duration_base_polynomial_

Fixed duration of each cubic polynomial describing the base motion.

Definition at line 77 of file parameters.h.

std::vector<bool> towr::Parameters::ee_in_contact_at_start_

True if the foot is initially in contact with the terrain.

Definition at line 83 of file parameters.h.

std::vector<VecTimes> towr::Parameters::ee_phase_durations_

Number and initial duration of each foot's swing and stance phases.

Definition at line 80 of file parameters.h.

int towr::Parameters::ee_polynomials_per_swing_phase_

Number of polynomials to parameterize foot movement during swing phases.

Definition at line 92 of file parameters.h.

double towr::Parameters::force_limit_in_norm_

The maximum allowable force [N] in normal direction.

Definition at line 98 of file parameters.h.

int towr::Parameters::force_polynomials_per_stance_phase_

Number of polynomials to parameterize each contact force during stance phase.

Definition at line 95 of file parameters.h.

double towr::Parameters::max_phase_duration_

When optimizing over phase duration, this is is maximum allowed.

Definition at line 89 of file parameters.h.

double towr::Parameters::min_phase_duration_

When optimizing over phase duration, this is the minimum allowed.

Definition at line 86 of file parameters.h.

double towr::Parameters::t_total_

Total duration [s] of the walking motion.

Definition at line 65 of file parameters.h.


The documentation for this struct was generated from the following files:


towr_core
Author(s): Alexander W. Winkler
autogenerated on Sat Apr 7 2018 02:15:58