55 cout <<
"************************************************************\n";
56 cout <<
" TOWR - Trajectory Optimization for Walking Robots (v1.4)\n";
57 cout <<
" \u00a9 Alexander W. Winkler\n";
58 cout <<
" https://github.com/ethz-adrl/towr\n";
59 cout <<
"************************************************************";
69 vars.insert(vars.end(), base_motion.begin(), base_motion.end());
72 vars.insert(vars.end(), ee_motion.begin(), ee_motion.end());
75 vars.insert(vars.end(), ee_force.begin(), ee_force.end());
95 std::vector<NodesVariables::Ptr>
98 std::vector<NodesVariables::Ptr> vars;
114 vars.push_back(spline_lin);
122 vars.push_back(spline_ang);
127 std::vector<NodesVariablesPhaseBased::Ptr>
130 std::vector<NodesVariablesPhaseBased::Ptr> vars;
135 auto nodes = std::make_shared<NodesVariablesEEMotion>(
143 Eigen::Vector3d euler(0.0, 0.0, yaw);
146 double x = final_ee_pos_W.x();
147 double y = final_ee_pos_W.y();
148 double z =
terrain_->GetHeight(x,y);
152 vars.push_back(nodes);
158 std::vector<NodesVariablesPhaseBased::Ptr>
161 std::vector<NodesVariablesPhaseBased::Ptr> vars;
165 auto nodes = std::make_shared<NodesVariablesEEForce>(
176 nodes->SetByLinearInterpolation(f_stance, f_stance, T);
177 vars.push_back(nodes);
183 std::vector<PhaseDurations::Ptr>
186 std::vector<PhaseDurations::Ptr> vars;
189 auto var = std::make_shared<PhaseDurations>(ee,
206 constraints.push_back(c);
224 default:
throw std::runtime_error(
"constraint not defined!");
271 auto duration_constraint = std::make_shared<TotalDurationConstraint>(T, ee);
272 c.push_back(duration_constraint);
285 constraints.push_back(c);
297 auto c = std::make_shared<ForceConstraint>(
terrain_,
300 constraints.push_back(c);
313 constraints.push_back(swing);
324 constraints.push_back(std::make_shared<SplineAccConstraint>
327 constraints.push_back(std::make_shared<SplineAccConstraint>
338 for (
auto c :
GetCost(pair.first, pair.second))
350 default:
throw std::runtime_error(
"cost not defined!");
std::pair< double, double > bound_phase_duration_
DynamicModel::Ptr dynamic_model_
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
double GetTotalTime() const
Total duration [s] of the motion.
std::vector< int > bounds_final_ang_vel_
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.
VecTimes GetBasePolyDurations() const
The durations of each base polynomial in the spline (lin+ang).
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.
int GetEECount() const
The number of endeffectors.
std::vector< int > bounds_final_lin_vel_
double dt_constraint_dynamic_
Interval at which the dynamic constraint is enforced.
bool IsOptimizeTimings() const
True if the phase durations should be optimized over.
sets NodeCost on force nodes
Builds splines from node values (pos/vel) and durations.
NodeSpline::Ptr base_linear_
std::vector< VecTimes > ee_phase_durations_
Number and initial duration of each foot's swing and stance phases.
static const std::string contact_schedule
const VectorXd p() const
read access to the zero-derivative of the state, e.g. position.
double force_limit_in_normal_direction_
The maximum allowable force [N] in normal direction.
sets TotalDurationConstraint
double dt_constraint_base_motion_
Interval at which the base motion constraint is enforced.
std::vector< int > bounds_final_ang_pos_
static std::string EEMotionNodes(uint ee)
NodeSpline::Ptr base_angular_
Node lin
linear position x,y,z and velocities.
std::vector< bool > ee_in_contact_at_start_
True if the foot is initially in contact with the terrain.
MatrixSXd GetRotationMatrixBaseToWorld(double t) const
Converts the Euler angles at time t to a rotation matrix.
static std::string EEForceNodes(uint ee)
UsedConstraints constraints_
Which constraints should be used in the optimization problem.
static const std::string base_ang_nodes
const VectorXd v() const
read access to the first-derivative of the state, e.g. velocity.
CostWeights costs_
Which costs should be used in the optimiation problem.
int GetPhaseCount(EEID ee) const
The number of phases allowed for endeffector ee.
KinematicModel::Ptr kinematic_model_
Node ang
angular euler roll, pitch, yaw and rates.
static const std::string base_lin_nodes