30 #ifndef TOWR_OPTIMIZATION_PARAMETERS_H_ 31 #define TOWR_OPTIMIZATION_PARAMETERS_H_ std::pair< double, double > bound_phase_duration_
The parameters to tune the optimization problem.
int GetEECount() const
The number of endeffectors.
int force_polynomials_per_stance_phase_
Number of polynomials to parameterize each contact force during stance phase.
sets RangeOfMotionConstraint
ConstraintName
Identifiers to be used to add certain constraints to the optimization problem.
sets BaseMotionConstraint
std::vector< int > bounds_final_ang_vel_
virtual ~Parameters()=default
sets NodeCost on endeffector velocity
std::vector< int > bounds_final_lin_pos_
which dimensions (x,y,z) of the final base state should be bounded
CostName
Indentifiers to be used to add certain costs to the optimization problem.
std::vector< std::pair< CostName, double > > CostWeights
int ee_polynomials_per_swing_phase_
Number of polynomials to parameterize foot movement during swing phases.
double dt_constraint_range_of_motion_
Interval at which the range of motion constraint is enforced.
std::vector< int > bounds_final_lin_vel_
double duration_base_polynomial_
Fixed duration of each cubic polynomial describing the base motion.
double dt_constraint_dynamic_
Interval at which the dynamic constraint is enforced.
sets NodeCost on force nodes
double GetTotalTime() const
Total duration [s] of the motion.
std::vector< VecTimes > ee_phase_durations_
Number and initial duration of each foot's swing and stance phases.
void OptimizePhaseDurations()
Specifies that timings of all feet, so the gait, should be optimized.
double force_limit_in_normal_direction_
The maximum allowable force [N] in normal direction.
int GetPhaseCount(EEID ee) const
The number of phases allowed for endeffector ee.
sets TotalDurationConstraint
double dt_constraint_base_motion_
Interval at which the base motion constraint is enforced.
std::vector< double > VecTimes
std::vector< int > bounds_final_ang_pos_
Parameters()
Default parameters to get started.
std::vector< bool > ee_in_contact_at_start_
True if the foot is initially in contact with the terrain.
UsedConstraints constraints_
Which constraints should be used in the optimization problem.
std::vector< ConstraintName > UsedConstraints
CostWeights costs_
Which costs should be used in the optimiation problem.
VecTimes GetBasePolyDurations() const
The durations of each base polynomial in the spline (lin+ang).
bool IsOptimizeTimings() const
True if the phase durations should be optimized over.