50 formulation.
terrain_ = std::make_shared<FlatGround>(0.0);
78 for (
auto c : formulation.
GetCosts())
87 auto solver = std::make_shared<ifopt::IpoptSolver>();
88 solver->SetOption(
"jacobian_approximation",
"exact");
89 solver->SetOption(
"max_cpu_time", 20.0);
100 cout <<
"\n====================\nMonoped trajectory:\n====================\n";
103 while (t<=solution.base_linear_->GetTotalTime() + 1e-5) {
104 cout <<
"t=" << t <<
"\n";
105 cout <<
"Base linear position x,y,z: \t";
106 cout << solution.
base_linear_->GetPoint(t).p().transpose() <<
"\t[m]" << endl;
108 cout <<
"Base Euler roll, pitch, yaw: \t";
109 Eigen::Vector3d rad = solution.
base_angular_->GetPoint(t).p();
110 cout << (rad/M_PI*180).transpose() <<
"\t[deg]" << endl;
112 cout <<
"Foot position x,y,z: \t";
113 cout << solution.
ee_motion_.at(0)->GetPoint(t).p().transpose() <<
"\t[m]" << endl;
115 cout <<
"Contact force x,y,z: \t";
116 cout << solution.
ee_force_.at(0)->GetPoint(t).p().transpose() <<
"\t[N]" << endl;
119 std::string foot_in_contact = contact?
"yes" :
"no";
120 cout <<
"Foot in contact: \t" + foot_in_contact << endl;
void AddCostSet(CostTerm::Ptr cost_set)
const VectorXd at(Dx deriv) const
Read the state value or it's derivatives by index.
Base class for robot specific kinematics and dynamics.
std::vector< PhaseDurations::Ptr > phase_durations_
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.
void PrintCurrent() const
std::vector< NodeSpline::Ptr > ee_force_
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.
void AddConstraintSet(ConstraintSet::Ptr constraint_set)
void AddVariableSet(VariableSet::Ptr variable_set)
std::vector< NodeSpline::Ptr > ee_motion_