56 vars.insert(vars.end(), base_motion.begin(), base_motion.end());
59 vars.insert(vars.end(), ee_motion.begin(), ee_motion.end());
62 vars.insert(vars.end(), ee_force.begin(), ee_force.end());
81 std::vector<Nodes::Ptr>
84 std::vector<Nodes::Ptr> vars;
94 vars.push_back(spline_lin);
102 vars.push_back(spline_ang);
107 std::vector<PhaseNodes::Ptr>
110 std::vector<PhaseNodes::Ptr> vars;
126 Eigen::Matrix3d w_R_b; w_R_b.setIdentity();
132 nodes->InitializeNodesTowardsGoal(
initial_ee_W_.at(ee), final_ee_pos_W, T);
142 vars.push_back(nodes);
149 std::vector<PhaseNodes::Ptr>
152 std::vector<PhaseNodes::Ptr> vars;
169 nodes->InitializeNodesTowardsGoal(f_stance, f_stance, T);
170 vars.push_back(nodes);
176 std::vector<PhaseDurations::Ptr>
179 std::vector<PhaseDurations::Ptr> vars;
183 auto var = std::make_shared<PhaseDurations>(ee,
200 constraints.push_back(c);
217 default:
throw std::runtime_error(
"constraint not defined!");
247 c.push_back(rom_constraints);
260 auto duration_constraint = std::make_shared<TotalDurationConstraint>(T, ee);
261 c.push_back(duration_constraint);
274 constraints.push_back(c);
286 auto c = std::make_shared<ForceConstraint>(
terrain_,
289 constraints.push_back(c);
302 constraints.push_back(swing);
313 constraints.push_back(std::make_shared<SplineAccConstraint>
316 constraints.push_back(std::make_shared<SplineAccConstraint>
327 for (
auto c :
GetCost(pair.first, pair.second))
338 default:
throw std::runtime_error(
"cost not defined!");
DynamicModel::Ptr dynamic_model_
ContraintPtrVec GetConstraints() const
ContraintPtrVec GetConstraint(ConstraintName name) const
CostPtrVec GetCost(const CostName &id, double weight) const
ContraintPtrVec MakeTotalTimeConstraint() const
std::vector< ifopt::ConstraintSet::Ptr > ContraintPtrVec
ContraintPtrVec MakeForceConstraint() const
int ee_polynomials_per_swing_phase_
Number of polynomials to parameterize foot movement during swing phases.
std::vector< PhaseNodes::Ptr > MakeEndeffectorVariables() const
UsedConstraints constraints_
Which constraints should be used in the optimization problem.
VariablePtrVec GetVariableSets()
double min_phase_duration_
When optimizing over phase duration, this is the minimum allowed.
std::vector< bool > ee_in_contact_at_start_
True if the foot is initially in contact with the terrain.
std::vector< PhaseDurations::Ptr > MakeContactScheduleVariables() const
CostWeights costs_
Which costs should be used in the optimiation problem.
double max_phase_duration_
When optimizing over phase duration, this is is maximum allowed.
ContraintPtrVec MakeTerrainConstraint() const
int GetPhaseCount(EEID ee) const
The number of phases allowed for endeffector ee.
int GetEECount() const
The number of endeffectors.
ContraintPtrVec GetCosts() const
ContraintPtrVec MakeRangeOfMotionBoxConstraint() const
std::vector< PhaseNodes::Ptr > MakeForceVariables() const
std::vector< ifopt::VariableSet::Ptr > VariablePtrVec
Holds pointers to fully constructed splines, that are linked to the optimization variables.
std::vector< ifopt::CostTerm::Ptr > CostPtrVec
NodeSpline::Ptr base_linear_
static const std::string contact_schedule
int force_polynomials_per_stance_phase_
Number of polynomials to parameterize each contact force during stance phase.
ContraintPtrVec MakeSwingConstraint() const
std::vector< VecTimes > ee_phase_durations_
Number and initial duration of each foot's swing and stance phases.
VecTimes GetBasePolyDurations() const
The durations of each base polynomial in the spline (lin+ang).
ContraintPtrVec MakeBaseRangeOfMotionConstraint() const
static std::string EEMotionNodes(uint ee)
NodeSpline::Ptr base_angular_
Node lin
linear position x,y,z and velocities.
double force_limit_in_norm_
The maximum allowable force [N] in normal direction.
bool OptimizeTimings() const
True if the phase durations should be optimized over.
ContraintPtrVec MakeBaseAccConstraint() const
static std::string EEForceNodes(uint ee)
CostPtrVec MakeForcesCost(double weight) const
ContraintPtrVec MakeDynamicConstraint() const
double t_total_
Total duration [s] of the walking motion.
static const std::string base_ang_nodes
SplineHolder spline_holder_
KinematicModel::Ptr kinematic_model_
std::vector< Nodes::Ptr > MakeBaseVariables() const
Node ang
angular euler roll, pitch, yaw and rates.
static const std::string base_lin_nodes