42 virtual double GetHeight(
double x,
double y)
const override {
return 0.0; };
51 nominal_stance_.at(0) = Eigen::Vector3d( 0.0, 0.0, -0.58);
52 max_dev_from_nominal_ << 0.25, 0.15, 0.2;
62 1.2, 5.5, 6.0, 0.0, -0.2, -0.01,
78 Eigen::Vector3d initial_foot_pos_W = Eigen::Vector3d::Zero();
100 towr.
SetParameters(goal, params, model, std::make_shared<FlatGround>());
110 cout <<
"\n====================\nMonoped trajectory:\n====================\n";
115 cout <<
"t=" << t <<
"\n";
116 cout <<
"Base linear position x,y,z: \t";
117 cout << x.
base_linear_->GetPoint(t).p().transpose() <<
"\t[m]" << endl;
119 cout <<
"Base Euler roll, pitch, yaw: \t";
120 Eigen::Vector3d rad = x.base_angular_->GetPoint(t).p();
121 cout << (rad/M_PI*180).transpose() <<
"\t[deg]" << endl;
123 cout <<
"Foot position x,y,z: \t";
124 cout << x.ee_motion_.at(0)->GetPoint(t).p().transpose() <<
"\t[m]" << endl;
126 cout <<
"Contact force x,y,z: \t";
127 cout << x.ee_force_.at(0)->GetPoint(t).p().transpose() <<
"\t[N]" << endl;
129 bool contact = x.phase_durations_.at(0)->IsContactPhase(t);
130 std::string foot_in_contact = contact?
"yes" :
"no";
131 cout <<
"Foot in contact: \t" + foot_in_contact << endl;
DynamicModel::Ptr dynamic_model_
virtual double GetHeight(double x, double y) const override
const VectorXd at(Dx deriv) const
std::vector< bool > ee_in_contact_at_start_
void SetInitialState(const BaseState &base, const FeetPos &feet)
void SetParameters(const BaseState &final_base, const Parameters ¶ms, const RobotModel &model, HeightMap::Ptr terrain)
NodeSpline::Ptr base_linear_
std::vector< VecTimes > ee_phase_durations_
SplineHolder GetSolution() const
KinematicModel::Ptr kinematic_model_