The parameters to tune the optimization problem. More...
#include <parameters.h>
Public Types | |
enum | ConstraintName { Dynamic, EndeffectorRom, TotalTime, Terrain, Force, Swing, BaseRom, BaseAcc } |
Identifiers to be used to add certain constraints to the optimization problem. More... | |
enum | CostName { ForcesCostID, EEMotionCostID } |
Indentifiers to be used to add certain costs to the optimization problem. More... | |
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... | |
double | GetTotalTime () const |
Total duration [s] of the motion. More... | |
bool | IsOptimizeTimings () const |
True if the phase durations should be optimized over. More... | |
void | OptimizePhaseDurations () |
Specifies that timings of all feet, so the gait, should be optimized. More... | |
Parameters () | |
Default parameters to get started. More... | |
virtual | ~Parameters ()=default |
Public Attributes | |
std::pair< double, double > | bound_phase_duration_ |
std::vector< int > | bounds_final_ang_pos_ |
std::vector< int > | bounds_final_ang_vel_ |
std::vector< int > | bounds_final_lin_pos_ |
which dimensions (x,y,z) of the final base state should be bounded More... | |
std::vector< int > | bounds_final_lin_vel_ |
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< VecTimes > | ee_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_normal_direction_ |
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... | |
The parameters to tune the optimization problem.
The number of parameters to tune is relatively small (~10), however, they do have a large impact on speed and convergence of the optimizer. Below we give some insights into how different values affect the solution and what should be taken into consideration when tuning these. For more background knowledge, refer to the corresponding paper.
A factor that strongly impacts the solution time is how often the DynamicConstraint and the RangeOfMotionConstraint are enforced along the trajectory (given by the values of dt_constraint_dynamic_ and dt_constraint_range_of_motion_). Increasing the discretization interval of e.g. dt_constraint_range_of_motion_ to 1.5s greatly speeds up the process. However, if the discretization is too coarse, the motion of e.g. the endeffector can move way outside the bounding boxes, as long it comes back inside this box at the few times the constraint is actually enforced. This is a valid solution to the optimization problem, but of course physically infeasible. Therefore, when the solution shows the feet shooting quickly through 3D space, dt_constraint_range_of_motion_ should probably be decreased. The same logic holds for too large dt_constraint_dynamic_: This can produce motion that violate the dynamics at most times, except exactly where they are enforced. This leads to unphysical motions that will be impossible to track on a real system. The more finely the constraint discretization is set, the more sure one can be that the dynamic model is being respected.
In order to shorten the solution time, another way is to use less polynomials, but each of longer duration. This can be achieved by increasing the duration_base_polynomial_. However, the longer this duration becomes, the less parameters (freedom), the solver has to find a solution that fullfills all the constraints, so it becomes more likely that no solution is found. This variable is related to dt_constraint_dynamic_ – if the dynamic constraint should be enforced at very short intervals, it is often also required that the base motion has enough freedom (short durations) to enable this.
One of the main reasons that the solver fails to find a solution, is when there are are not enough steps available to reach a goal position that is either too far away, or the terrain too complex. The number of steps per leg and their initial durations are set by ee_phase_durations_. On the other hand, too many steps per leg are hardly an issue and the solver simply generates more short steps, but finds a solution nonetheless. Therefore:
Sometimes the solution to the optimization problem looks jerky, with the forces and base motion quickly jittering back and forth. This is because by default, we don't include any costs_ in the formulation. The solver has too many optimization variables (degrees of freedom) to modify and only few constraints that restrict the motion, so these extra and unnecessary values can be set to extreme values. The cleanest way to counter this is to add a cost term that e.g. penalizes base and endeffector accelerations. See Costs for some inspiration. We try to avoid cost terms if possible, as they require tuning different weighing parameters w.r.t. each other and make the problem slower. Other ways to remove the jittering are as follows:
The solver is able to modify the gait to best achieve a given task. This can be turned on by calling OptimizePhaseDurations(). This can help the solver find a solution to terrains which cannot be crossed with the initialized gait. However, this optimization over the phase durations, which affect the entire motion of that endeffector, reduce the sparsity of the formulation. This increases the chances of getting stuck in local minima, as well as increases the computation time. Therefore, this option should be treated with caution. An alternative to turning on this option is initializing with different gaits and/or changing the parameters described above.
Definition at line 133 of file parameters.h.
using towr::Parameters::CostWeights = std::vector<std::pair<CostName, double>> |
Definition at line 156 of file parameters.h.
using towr::Parameters::EEID = unsigned int |
Definition at line 159 of file parameters.h.
using towr::Parameters::UsedConstraints = std::vector<ConstraintName> |
Definition at line 157 of file parameters.h.
using towr::Parameters::VecTimes = std::vector<double> |
Definition at line 158 of file parameters.h.
Identifiers to be used to add certain constraints to the optimization problem.
Enumerator | |
---|---|
Dynamic |
sets DynamicConstraint |
EndeffectorRom | |
TotalTime | |
Terrain |
sets TerrainConstraint |
Force |
sets ForceConstraint |
Swing |
sets SwingConstraint |
BaseRom |
sets BaseMotionConstraint |
BaseAcc |
sets SplineAccConstraint |
Definition at line 139 of file parameters.h.
Indentifiers to be used to add certain costs to the optimization problem.
Enumerator | |
---|---|
ForcesCostID |
sets NodeCost on force nodes |
EEMotionCostID |
sets NodeCost on endeffector velocity |
Definition at line 152 of file parameters.h.
towr::Parameters::Parameters | ( | ) |
Default parameters to get started.
Definition at line 40 of file parameters.cc.
|
virtualdefault |
Parameters::VecTimes towr::Parameters::GetBasePolyDurations | ( | ) | const |
The durations of each base polynomial in the spline (lin+ang).
Definition at line 83 of file parameters.cc.
int towr::Parameters::GetEECount | ( | ) | const |
The number of endeffectors.
Definition at line 107 of file parameters.cc.
int towr::Parameters::GetPhaseCount | ( | EEID | ee | ) | const |
The number of phases allowed for endeffector ee.
Definition at line 101 of file parameters.cc.
double towr::Parameters::GetTotalTime | ( | ) | const |
Total duration [s] of the motion.
Definition at line 113 of file parameters.cc.
bool towr::Parameters::IsOptimizeTimings | ( | ) | const |
True if the phase durations should be optimized over.
Definition at line 129 of file parameters.cc.
void towr::Parameters::OptimizePhaseDurations | ( | ) |
Specifies that timings of all feet, so the gait, should be optimized.
Definition at line 77 of file parameters.cc.
std::pair<double,double> towr::Parameters::bound_phase_duration_ |
Minimum and maximum time [s] for each phase (swing,stance).
Only used when optimizing over phase durations. Make sure max time is less than total duration of trajectory, or segfault. limiting this range can help convergence when optimizing gait.
Definition at line 212 of file parameters.h.
std::vector<int> towr::Parameters::bounds_final_ang_pos_ |
Definition at line 201 of file parameters.h.
std::vector<int> towr::Parameters::bounds_final_ang_vel_ |
Definition at line 201 of file parameters.h.
std::vector<int> towr::Parameters::bounds_final_lin_pos_ |
which dimensions (x,y,z) of the final base state should be bounded
Definition at line 201 of file parameters.h.
std::vector<int> towr::Parameters::bounds_final_lin_vel_ |
Definition at line 201 of file parameters.h.
UsedConstraints towr::Parameters::constraints_ |
Which constraints should be used in the optimization problem.
Definition at line 174 of file parameters.h.
CostWeights towr::Parameters::costs_ |
Which costs should be used in the optimiation problem.
Definition at line 177 of file parameters.h.
double towr::Parameters::dt_constraint_base_motion_ |
Interval at which the base motion constraint is enforced.
Definition at line 186 of file parameters.h.
double towr::Parameters::dt_constraint_dynamic_ |
Interval at which the dynamic constraint is enforced.
Definition at line 180 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 183 of file parameters.h.
double towr::Parameters::duration_base_polynomial_ |
Fixed duration of each cubic polynomial describing the base motion.
Definition at line 189 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 171 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 168 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 192 of file parameters.h.
double towr::Parameters::force_limit_in_normal_direction_ |
The maximum allowable force [N] in normal direction.
Definition at line 198 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 195 of file parameters.h.