diff --git a/config/ipopt.opt b/config/ipopt.opt index cf4425607..e355f93f9 100644 --- a/config/ipopt.opt +++ b/config/ipopt.opt @@ -30,7 +30,7 @@ tol 0.001 # usually 0.01 #bound_relax_factor 0.01 -max_cpu_time 10 +max_cpu_time 100 #max_iter 0 #bound_frac 0.5 diff --git a/include/xpp/composite.h b/include/xpp/composite.h index bf5aedd52..7ce758d89 100644 --- a/include/xpp/composite.h +++ b/include/xpp/composite.h @@ -15,7 +15,7 @@ #include #include -#include "bound.h" +#include "nlp_bound.h" namespace xpp { namespace opt { diff --git a/include/xpp/constraints/dynamic_constraint.h b/include/xpp/constraints/dynamic_constraint.h index 628d7a64a..297bb23f6 100644 --- a/include/xpp/constraints/dynamic_constraint.h +++ b/include/xpp/constraints/dynamic_constraint.h @@ -13,10 +13,10 @@ #include #include -#include #include #include #include +#include #include #include diff --git a/include/xpp/constraints/force_constraint.h b/include/xpp/constraints/force_constraint.h index 911a788bd..5a8fe1795 100644 --- a/include/xpp/constraints/force_constraint.h +++ b/include/xpp/constraints/force_constraint.h @@ -10,9 +10,9 @@ #include -#include #include #include +#include #include namespace xpp { diff --git a/include/xpp/constraints/linear_constraint.h b/include/xpp/constraints/linear_constraint.h index ad742bd69..ca252dde1 100644 --- a/include/xpp/constraints/linear_constraint.h +++ b/include/xpp/constraints/linear_constraint.h @@ -10,9 +10,9 @@ #include -#include #include #include +#include namespace xpp { diff --git a/include/xpp/constraints/range_of_motion_constraint.h b/include/xpp/constraints/range_of_motion_constraint.h index f2445da39..65c98366e 100644 --- a/include/xpp/constraints/range_of_motion_constraint.h +++ b/include/xpp/constraints/range_of_motion_constraint.h @@ -13,9 +13,9 @@ #include #include -#include #include #include +#include #include #include #include diff --git a/include/xpp/constraints/spline_constraint.h b/include/xpp/constraints/spline_constraint.h index eb8599f90..143df61e6 100644 --- a/include/xpp/constraints/spline_constraint.h +++ b/include/xpp/constraints/spline_constraint.h @@ -12,9 +12,9 @@ #include #include -#include #include #include +#include #include #include #include diff --git a/include/xpp/constraints/swing_constraint.h b/include/xpp/constraints/swing_constraint.h index c59de777a..4a092dde5 100644 --- a/include/xpp/constraints/swing_constraint.h +++ b/include/xpp/constraints/swing_constraint.h @@ -10,8 +10,8 @@ #include -#include #include +#include #include namespace xpp { @@ -31,7 +31,7 @@ class SwingConstraint : public Constraint { private: EEMotionNodes::Ptr ee_motion_; - double t_swing_avg_ = 100.2; + double t_swing_avg_ = 0.3; // double swing_height_in_world_ = 0.06; // hacky way to lift legs }; diff --git a/include/xpp/constraints/terrain_constraint.h b/include/xpp/constraints/terrain_constraint.h index d346808c0..0f306493d 100644 --- a/include/xpp/constraints/terrain_constraint.h +++ b/include/xpp/constraints/terrain_constraint.h @@ -10,9 +10,9 @@ #include -#include #include #include +#include #include namespace xpp { diff --git a/include/xpp/constraints/time_discretization_constraint.h b/include/xpp/constraints/time_discretization_constraint.h index edd7100eb..0af06e0c0 100644 --- a/include/xpp/constraints/time_discretization_constraint.h +++ b/include/xpp/constraints/time_discretization_constraint.h @@ -11,8 +11,8 @@ #include #include -#include #include +#include namespace xpp { diff --git a/include/xpp/dynamic_model.h b/include/xpp/dynamic_model.h index 7e5387984..30316e761 100644 --- a/include/xpp/dynamic_model.h +++ b/include/xpp/dynamic_model.h @@ -64,7 +64,7 @@ class DynamicModel { virtual void SetInitialGait(int gait_id) {}; // does nothing if not overwritten - std::vector GetNormalizedInitialTimings(EndeffectorID ee) const; + std::vector GetNormalizedInitialTimings(EndeffectorID ee); protected: ComPos com_pos_; @@ -74,6 +74,7 @@ class DynamicModel { std::vector ee_ids_; ContactTimings contact_timings_; + void NormalizeTimesToOne(EndeffectorID ee); EndeffectorsPos nominal_stance_; Vector3d max_dev_from_nominal_; diff --git a/include/xpp/height_map.h b/include/xpp/height_map.h index 4a528250f..62c50ddcd 100644 --- a/include/xpp/height_map.h +++ b/include/xpp/height_map.h @@ -81,10 +81,10 @@ class Block : public HeightMap { private: double block_start = 1.5; - double length_ = 2.0; - double height_ = 1.0; // [m] + double length_ = 1.0; + double height_ = 0.4; // [m] - double eps_ = 0.1; // approximate as slope + double eps_ = 0.05; // approximate as slope const double slope_ = height_/eps_; }; @@ -95,7 +95,7 @@ class Stairs : public HeightMap { virtual double GetHeight(double x, double y) const override; private: - double first_step_start_ = 0.7; + double first_step_start_ = 1.5; double first_step_width_ = 0.4; double height_first_step = 0.2; double height_second_step = 0.4; @@ -112,9 +112,9 @@ class Gap : public HeightMap { virtual double GetHeightDerivWrtXX(double x, double y) const override; private: - const double gap_start_ = 1.0; - const double w = 0.7; // gap width - const double h = 1.0; + const double gap_start_ = 1.5; + const double w = 0.5; // gap width + const double h = 0.4; const double slope_ = h/w; const double dx = w/2; // gap witdh 2 diff --git a/include/xpp/nlp.h b/include/xpp/nlp.h index cf06a3ccb..27c89d861 100644 --- a/include/xpp/nlp.h +++ b/include/xpp/nlp.h @@ -12,8 +12,8 @@ #include #include -#include "bound.h" #include +#include "nlp_bound.h" namespace xpp { namespace opt { diff --git a/include/xpp/bound.h b/include/xpp/nlp_bound.h similarity index 63% rename from include/xpp/bound.h rename to include/xpp/nlp_bound.h index 76849cec2..becf0a2a8 100644 --- a/include/xpp/bound.h +++ b/include/xpp/nlp_bound.h @@ -15,8 +15,8 @@ namespace opt { /** Upper and lower bound on either constraints or optimization variables */ -struct Bound { - Bound(double lower = 0.0, double upper = 0.0) { +struct NLPBound { + NLPBound(double lower = 0.0, double upper = 0.0) { lower_ = lower; upper_ = upper; } @@ -34,12 +34,12 @@ struct Bound { } }; -static const Bound kNoBound_ = Bound(-1.0e20, +1.0e20);; -static const Bound BoundZero = Bound(0.0, 0.0); -static const Bound BoundGreaterZero = Bound(0.0, +1.0e20); -static const Bound BoundSmallerZero = Bound(-1.0e20, 0.0); +static const NLPBound kNoBound_ = NLPBound(-1.0e20, +1.0e20);; +static const NLPBound BoundZero = NLPBound(0.0, 0.0); +static const NLPBound BoundGreaterZero = NLPBound(0.0, +1.0e20); +static const NLPBound BoundSmallerZero = NLPBound(-1.0e20, 0.0); -using VecBound = std::vector; +using VecBound = std::vector; } } diff --git a/include/xpp/quadruped_gait_generator.h b/include/xpp/quadruped_gait_generator.h index 0f6e86a3c..0bf4f95fc 100644 --- a/include/xpp/quadruped_gait_generator.h +++ b/include/xpp/quadruped_gait_generator.h @@ -16,17 +16,18 @@ namespace xpp { namespace quad { -enum QuadrupedGaits {Stand=0, Leglift, Walk, TrotFly, Trot, Pace, Bound, Pronk, kNumGaits}; +enum QuadrupedGaits {Stand=0, Leglift, Walk, WalkOverlap, TrotFly, Trot, Pace, Bound, Pronk, kNumGaits}; static std::map gait_names = { - {Stand , "Stand"}, - {Leglift, "Leglift"}, - {Walk , "Walk"}, - {Trot, "Trot"}, - {TrotFly, "TrotFly"}, - {Pace, "Pace"}, - {Bound, "Bound"}, - {Pronk, "Pronk"} + {Stand, "Stand"}, + {Leglift, "Leglift"}, + {Walk, "Walk"}, + {WalkOverlap, "WalkOverlap"}, + {Trot, "Trot"}, + {TrotFly, "TrotFly"}, + {Pace, "Pace"}, + {Bound, "Bound"}, + {Pronk, "Pronk"} }; class QuadrupedGaitGenerator { @@ -36,25 +37,35 @@ class QuadrupedGaitGenerator { using ContactState = EndeffectorsBool; using VecTimes = std::vector; using FootDurations = std::vector; + using GaiInfo = std::pair>; QuadrupedGaitGenerator (); virtual ~QuadrupedGaitGenerator (); FootDurations GetContactSchedule() const; - void SetGait(QuadrupedGaits gait); + void SetGaits(const std::vector& gaits); - void SetDurationsStand(); - void SetDurationsLeglift(); - void SetDurationsWalk(); - void SetDurationsTrot(); - void SetDurationsTrotFly(); - void SetDurationsPace(); - void SetDurationsBound(); - void SetDurationsPronk(); private: - VecTimes phase_times_; - std::vector phase_contacts_; + std::vector times_; + std::vector contacts_; + + GaiInfo GetGait(QuadrupedGaits gait) const; + + GaiInfo GetDurationsStand() const; + GaiInfo GetDurationsLeglift() const; + GaiInfo GetDurationsWalk() const; + GaiInfo GetDurationsWalkOverlap() const; + GaiInfo GetDurationsTrot() const; + GaiInfo GetDurationsTrotFly() const; + GaiInfo GetDurationsPace() const; + GaiInfo GetDurationsBound() const; + GaiInfo GetDurationsPronk() const; + +// /** +// * So the total duration of all phase times equals 1 second. +// */ +// void NormalizeTimesToOne(); // naming convention:, where the circle is is contact, front is right ->. diff --git a/include/xpp/variables/contact_schedule.h b/include/xpp/variables/contact_schedule.h index 7a72823fa..9ea274d40 100644 --- a/include/xpp/variables/contact_schedule.h +++ b/include/xpp/variables/contact_schedule.h @@ -12,9 +12,9 @@ #include #include -#include #include #include +#include #include "phase_nodes.h" @@ -58,7 +58,7 @@ class ContactSchedule : public Component { private: bool first_phase_in_contact_ = true; double t_total_; - Bound phase_duration_bounds_; + NLPBound phase_duration_bounds_; std::vector observers_; PhaseNodesPtr GetObserver(const std::string& id) const; diff --git a/include/xpp/variables/node_values.h b/include/xpp/variables/node_values.h index 935c0c4dd..8b0a4a781 100644 --- a/include/xpp/variables/node_values.h +++ b/include/xpp/variables/node_values.h @@ -13,9 +13,9 @@ #include #include -#include #include #include +#include #include #include diff --git a/include/xpp/variables/phase_nodes.h b/include/xpp/variables/phase_nodes.h index 5cc85be32..2c7646fa2 100644 --- a/include/xpp/variables/phase_nodes.h +++ b/include/xpp/variables/phase_nodes.h @@ -11,8 +11,8 @@ #include #include -#include #include +#include #include "node_values.h" diff --git a/src/centroidal_model.cc b/src/centroidal_model.cc index 19aeffcd4..56940fbd2 100644 --- a/src/centroidal_model.cc +++ b/src/centroidal_model.cc @@ -128,22 +128,24 @@ static Eigen::Matrix3d BuildInertiaTensor( // specific models MonopedModel::MonopedModel () - :CentroidalModel(80, + :CentroidalModel(20, BuildInertiaTensor( 1.209488,5.5837,6.056973,0.00571,-0.190812,-0.012668), 1) { map_id_to_ee_["E0"] = E0; nominal_stance_.At(E0) = Vector3d( 0.0, 0.0, -0.58); - max_dev_from_nominal_ << 0.15, 0.15, 0.12; - normal_force_max_ = 10000; - - double f = 0.2; - double c = 0.2; - contact_timings_.at(E0) = {c, f, c, f, c, f, c, f, c, f, c, f, c}; + max_dev_from_nominal_ << 0.15, 0.15, 0.15; + normal_force_max_ = 2000; + + double f = 0.2; + double fh = 0.3; + double c = 0.15; + contact_timings_.at(E0) = {c, f, c, f, c, f, c, fh, c, 0.4, c, + f, c, f, c, fh, c, f, c, f, c, f, c}; } BipedModel::BipedModel () - :CentroidalModel(80, + :CentroidalModel(20, BuildInertiaTensor( 1.209488,5.5837,6.056973,0.00571,-0.190812,-0.012668), 2) { @@ -156,15 +158,21 @@ BipedModel::BipedModel () nominal_stance_.At(map_id_to_ee_.at(R)) << 0.0, -y_nominal_b, z_nominal_b; max_dev_from_nominal_ << 0.15, 0.15, 0.15; - normal_force_max_ = 10000; + normal_force_max_ = 400; - // timings normalized anyway - double f = 0.2; - double c = 0.2; + +// quad::QuadrupedGaitGenerator gait_gen; +// gait_gen.SetGaits({quad::Trot, quad::TrotFly, quad::Bound, quad::Pace}); +// ContactTimings quad_timings = gait_gen.GetContactSchedule(); +// contact_timings_.at(kMapIDToEE.at(L)) = quad_timings.at(quad::kMapIDToEE.at(quad::LF)); +// contact_timings_.at(kMapIDToEE.at(R)) = quad_timings.at(quad::kMapIDToEE.at(quad::RF)); + + double f = 0.5; + double c = 0.5; double offset = c; - contact_timings_.at(kMapIDToEE.at(L)) = {c+offset,f,c,f,c,f,c,f,c}; - contact_timings_.at(kMapIDToEE.at(R)) = { c,f,c,f,c,f,c,f, c+offset}; + contact_timings_.at(kMapIDToEE.at(L)) = {c+offset,f,c,f,c,f,c,f,c,f,c}; + contact_timings_.at(kMapIDToEE.at(R)) = { c,f,c,f,c,f,c,f,c,f, c+offset}; } HyqModel::HyqModel () @@ -194,7 +202,8 @@ HyqModel::SetInitialGait (int gait_id) { using namespace xpp::quad; QuadrupedGaitGenerator gait_gen; - gait_gen.SetGait(static_cast(gait_id)); +// gait_gen.SetGaits({static_cast(gait_id)}); + gait_gen.SetGaits({WalkOverlap, TrotFly, Bound, Pace}); contact_timings_ = gait_gen.GetContactSchedule(); } @@ -222,25 +231,27 @@ AnymalModel::AnymalModel () nominal_stance_.At(map_id_to_ee_.at(RH)) << -x_nominal_b, -y_nominal_b, z_nominal_b; //spring_clean_ reduced endeffector range of motion - max_dev_from_nominal_ << 0.18, 0.08, 0.07; // spring_clean_ reduce y range - normal_force_max_ = 1000; // spring_clean_ halved the max force +// max_dev_from_nominal_ << 0.18, 0.08, 0.07; // for motions on real ANYmal + max_dev_from_nominal_ << 0.18, 0.13, 0.09; // spring_clean_ reduce y range + normal_force_max_ = 2000; // spring_clean_ halved the max force }; void AnymalModel::SetInitialGait (int gait_id) { using namespace xpp::quad; - QuadrupedGaitGenerator gait_gen; - gait_gen.SetGait(static_cast(gait_id)); - contact_timings_ = gait_gen.GetContactSchedule(); - - // double f = 0.4; // [s] t_free - // double c = 0.4; // [s] t_contact - // double t_offset = f; - // contact_timings_.at(kMapIDToEE.at(LH)) = {t_offset + c, f, c, f, c, f, c, f, c }; - // contact_timings_.at(kMapIDToEE.at(LF)) = { c, f, c, f, c, f, c, f, c + t_offset}; - // contact_timings_.at(kMapIDToEE.at(RH)) = { c, f, c, f, c, f, c, f, c + t_offset}; - // contact_timings_.at(kMapIDToEE.at(RF)) = {t_offset + c, f, c, f, c, f, c, f, c }; +// QuadrupedGaitGenerator gait_gen; +// gait_gen.SetGaits({static_cast(gait_id)}); +// gait_gen.SetGaits({Trot, Trot}); +// contact_timings_ = gait_gen.GetContactSchedule(); + + double f = 0.4; // [s] t_free + double c = 0.4; // [s] t_contact + double t_offset = f; + contact_timings_.at(kMapIDToEE.at(LH)) = {t_offset + c, f, c, f, c, f, c, f, c }; + contact_timings_.at(kMapIDToEE.at(LF)) = { c, f, c, f, c, f, c, f, c + t_offset}; + contact_timings_.at(kMapIDToEE.at(RH)) = { c, f, c, f, c, f, c, f, c + t_offset}; + contact_timings_.at(kMapIDToEE.at(RF)) = {t_offset + c, f, c, f, c, f, c, f, c }; } diff --git a/src/contact_schedule.cc b/src/contact_schedule.cc index 07b3e296d..3d0e09781 100644 --- a/src/contact_schedule.cc +++ b/src/contact_schedule.cc @@ -33,7 +33,7 @@ ContactSchedule::ContactSchedule (EndeffectorID ee, for (auto d : timings) durations_.push_back(d*t_total); - phase_duration_bounds_ = Bound(min_duration, max_duration); + phase_duration_bounds_ = NLPBound(min_duration, max_duration); first_phase_in_contact_ = true; SetRows(durations_.size()-1); // since last phase-duration is not optimized over } @@ -198,7 +198,7 @@ DurationConstraint::GetValues () const VecBound DurationConstraint::GetBounds () const { - return VecBound(GetRows(), Bound(0.1, T_total_-0.2)); + return VecBound(GetRows(), NLPBound(0.1, T_total_-0.2)); } void diff --git a/src/depr/contact_load_constraint.cc b/src/depr/contact_load_constraint.cc index dabe67a32..9b08348a5 100644 --- a/src/depr/contact_load_constraint.cc +++ b/src/depr/contact_load_constraint.cc @@ -10,9 +10,9 @@ #include #include -#include #include #include +#include namespace xpp { namespace opt { diff --git a/src/depr/convexity_constraint.cc b/src/depr/convexity_constraint.cc index dffa2e4f4..63ebdd75e 100644 --- a/src/depr/convexity_constraint.cc +++ b/src/depr/convexity_constraint.cc @@ -15,8 +15,8 @@ #include -#include #include +#include namespace xpp { namespace opt { diff --git a/src/depr/obstacle_constraint.cc b/src/depr/obstacle_constraint.cc index fff7364c1..171963445 100644 --- a/src/depr/obstacle_constraint.cc +++ b/src/depr/obstacle_constraint.cc @@ -8,7 +8,7 @@ #include #include -#include +#include namespace xpp { namespace opt { diff --git a/src/depr/optimization_variables.cc b/src/depr/optimization_variables.cc index 069cf626a..e8fe60ec7 100644 --- a/src/depr/optimization_variables.cc +++ b/src/depr/optimization_variables.cc @@ -9,7 +9,7 @@ #include -#include +#include namespace xpp { namespace opt { diff --git a/src/depr/polygon_center_constraint.cc b/src/depr/polygon_center_constraint.cc index 50b8b8fdc..26fae597e 100644 --- a/src/depr/polygon_center_constraint.cc +++ b/src/depr/polygon_center_constraint.cc @@ -14,9 +14,9 @@ #include -#include #include #include +#include namespace xpp { namespace opt { diff --git a/src/dynamic_constraint.cc b/src/dynamic_constraint.cc index 301521d85..9cf5495be 100644 --- a/src/dynamic_constraint.cc +++ b/src/dynamic_constraint.cc @@ -73,7 +73,7 @@ DynamicConstraint::UpdateBoundsAtInstance(double t, int k, VecBound& bounds) con { for (auto dim : AllDim6D) { if (dim == LZ) - bounds.at(GetRow(k,dim)) = Bound(gravity_, gravity_); + bounds.at(GetRow(k,dim)) = NLPBound(gravity_, gravity_); else bounds.at(GetRow(k,dim)) = BoundZero; } diff --git a/src/dynamic_model.cc b/src/dynamic_model.cc index 07ed6865f..705fc0254 100644 --- a/src/dynamic_model.cc +++ b/src/dynamic_model.cc @@ -48,13 +48,19 @@ xpp::opt::DynamicModel::GetEndeffectorNames () const } std::vector -DynamicModel::GetNormalizedInitialTimings (EndeffectorID ee) const +DynamicModel::GetNormalizedInitialTimings (EndeffectorID ee) { - // normalize vector, so equals 1.0 - auto v = contact_timings_.at(ee); - double sum = std::accumulate(v.begin(), v.end(), 0.0); - std::transform(v.begin(), v.end(), v.begin(), [sum](auto& e){ return e/sum;}); - return v; + NormalizeTimesToOne(ee); + return contact_timings_.at(ee); +} + +void +DynamicModel::NormalizeTimesToOne(EndeffectorID ee) +{ + auto& v = contact_timings_.at(ee); // shorthand + double total_time = std::accumulate(v.begin(), v.end(), 0.0); + std::transform(v.begin(), v.end(), v.begin(), + [total_time](double t_phase){ return t_phase/total_time;}); } DynamicModel::~DynamicModel () diff --git a/src/force_constraint.cc b/src/force_constraint.cc index fd8da0f1d..a7f5fdd3d 100644 --- a/src/force_constraint.cc +++ b/src/force_constraint.cc @@ -84,7 +84,7 @@ ForceConstraint::GetBounds () const for (int i=0; iGetNodes().size(); ++i) { if (ee_force_->IsStanceNode(i)) { - bounds.push_back(Bound(0.0, force_limit_normal_direction_)); // unilateral forces + bounds.push_back(NLPBound(0.0, force_limit_normal_direction_)); // unilateral forces bounds.push_back(BoundSmallerZero); // f_t1 < mu*n bounds.push_back(BoundGreaterZero); // f_t1 > -mu*n bounds.push_back(BoundSmallerZero); // f_t2 < mu*n diff --git a/src/linear_constraint.cc b/src/linear_constraint.cc index 5b336297c..eb52f7698 100644 --- a/src/linear_constraint.cc +++ b/src/linear_constraint.cc @@ -7,8 +7,8 @@ #include -#include #include +#include namespace xpp { namespace opt { @@ -44,7 +44,7 @@ LinearEqualityConstraint::GetBounds () const VecBound bounds; for (int i=0; i(); terrain_ = std::make_shared(); -// BuildDefaultInitialState(); + BuildDefaultInitialState(); } MotionOptimizerFacade::~MotionOptimizerFacade () { } -//void -//MotionOptimizerFacade::BuildDefaultInitialState () -//{ -// auto p_nom_B = model_->GetNominalStanceInBase(); -// -// inital_base_.lin.p_ << 0.0, 0.0, -p_nom_B.At(E0).z(); -// inital_base_.ang.p_ << 0.0, 0.0, 0.0; // euler (roll, pitch, yaw) -// -// initial_ee_W_.SetCount(model_->GetEECount()); -// for (auto ee : initial_ee_W_.GetEEsOrdered()) { -// initial_ee_W_.At(ee) = p_nom_B.At(ee) + inital_base_.lin.p_; -// initial_ee_W_.At(ee).z() = 0.0; -// } -//} +void +MotionOptimizerFacade::BuildDefaultInitialState () +{ + auto p_nom_B = model_->GetNominalStanceInBase(); + + inital_base_.lin.p_ << 0.0, 0.0, -p_nom_B.At(E0).z(); + inital_base_.ang.p_ << 0.0, 0.0, 0.0; // euler (roll, pitch, yaw) + + initial_ee_W_.SetCount(model_->GetEECount()); + for (auto ee : initial_ee_W_.GetEEsOrdered()) { + initial_ee_W_.At(ee) = p_nom_B.At(ee) + inital_base_.lin.p_; + initial_ee_W_.At(ee).z() = 0.0; + } +} MotionOptimizerFacade::OptimizationVariablesPtr MotionOptimizerFacade::BuildVariables () const @@ -99,10 +99,10 @@ MotionOptimizerFacade::BuildVariables () const ee_motion->InitializeVariables(initial_ee_W_.At(ee), final_ee_pos_W, contact_schedule.at(ee)->GetTimePerPhase()); - ee_motion->AddStartBound(kPos, {X,Y}, initial_ee_W_.At(ee)); // spring_clean_ only xy, z given by terrain + ee_motion->AddStartBound(kPos, {X,Y}, initial_ee_W_.At(ee)); // only xy, z given by terrain //spring_clean_ fixed final footholds - ee_motion->AddFinalBound(kPos, {X,Y}, final_ee_pos_W); // fixes the final footholds + ee_motion->AddFinalBound(kPos, {X,Y}, final_ee_pos_W); opt_variables->AddComponent(ee_motion); } diff --git a/src/node_values.cc b/src/node_values.cc index 9aa1240aa..090f8a871 100644 --- a/src/node_values.cc +++ b/src/node_values.cc @@ -254,7 +254,7 @@ NodeValues::SetBoundsAboveGround () for (int idx=0; idx& gaits) +{ + // initialize with stance phase + times_ = { 0.3 }; + contacts_ = { BB_ }; + + for (QuadrupedGaits g : gaits) { + auto info = GetGait(g); + std::vector t = info.first; + std::vector c = info.second; + assert(t.size() == c.size()); // make sure every phase has a time + + times_.insert (times_.end(), t.begin(), t.end()); + contacts_.insert(contacts_.end(), c.begin(), c.end()); + + // insert short time where all legs are in contact between gaits +// times_.push_back(0.2); +// contacts_.push_back(BB_); + } + + // insert final stance phase + times_.push_back(0.5); + contacts_.push_back(BB_); +// NormalizeTimesToOne(); +} + +QuadrupedGaitGenerator::GaiInfo +QuadrupedGaitGenerator::GetGait(QuadrupedGaits gait) const +{ + switch (gait) { + case Stand: return GetDurationsStand(); + case Leglift: return GetDurationsLeglift(); + case Walk: return GetDurationsWalk(); + case WalkOverlap: return GetDurationsWalkOverlap(); + case Trot: return GetDurationsTrot(); + case TrotFly: return GetDurationsTrotFly(); + case Pace: return GetDurationsPace(); + case Bound: return GetDurationsBound(); + case Pronk: return GetDurationsPronk(); + default: assert(false); // gait not implemented + } +} + +// already in dynamic model +//void +//QuadrupedGaitGenerator::NormalizeTimesToOne() +//{ +// double total_time = std::accumulate(times_.begin(), times_.end(), 0.0); +// std::transform(times_.begin(), times_.end(), times_.begin(), +// [total_time](double t_phase){ return t_phase/total_time;}); +//} + +QuadrupedGaitGenerator::GaiInfo +QuadrupedGaitGenerator::GetDurationsStand () const { - phase_times_ = + auto times = { 1.0, }; - phase_contacts_ = + auto contacts = { BB_, }; + + return std::make_pair(times, contacts); } -void -QuadrupedGaitGenerator::SetDurationsLeglift () +QuadrupedGaitGenerator::GaiInfo +QuadrupedGaitGenerator::GetDurationsLeglift () const { - phase_times_ = + auto phase_times = { 0.3, - 0.3, - 0.3 }; - phase_contacts_ = + auto phase_contacts = { - BB_, Bb_, - BB_ }; + + return std::make_pair(phase_times, phase_contacts); } -void -QuadrupedGaitGenerator::SetDurationsPronk () +QuadrupedGaitGenerator::GaiInfo +QuadrupedGaitGenerator::GetDurationsPronk () const { - phase_times_ = + auto times = { - 0.3, - 0.2, 0.4, 0.2, - 0.3 + 0.1, 0.3, + 0.1, 0.3, + 0.1, 0.3, }; - phase_contacts_ = + auto phase_contacts = { - BB_, - II_, BB_, II_, - BB_ + II_, BB_, + II_, BB_, + II_, BB_, }; + + return std::make_pair(times, phase_contacts); } -void -QuadrupedGaitGenerator::SetDurationsWalk () +QuadrupedGaitGenerator::GaiInfo +QuadrupedGaitGenerator::GetDurationsWalk () const { - double t_phase = 0.2; - double t_trans = 0.1; - phase_times_ = + double t_phase = 0.3; + double t_trans = 0.13; + auto times = { - 0.3, t_phase, t_trans, t_phase, t_phase, t_trans, t_phase, t_phase, t_trans, t_phase, t_phase, t_trans, t_phase, - t_phase, t_trans, t_phase, t_phase, t_trans, t_phase, - 0.2, }; - phase_contacts_ = + auto phase_contacts = { - BB_, bB_, bb_, Bb_, PB_, PP_, BP_, bB_, bb_, Bb_, PB_, PP_, BP_, - BB_, }; + + return std::make_pair(times, phase_contacts); } -void -QuadrupedGaitGenerator::SetDurationsTrot () +QuadrupedGaitGenerator::GaiInfo +QuadrupedGaitGenerator::GetDurationsWalkOverlap () const +{ + double three = 0.3; + double lateral = 0.13; + double diagonal = 0.13; + + auto times = + { + three, lateral, three, + diagonal, + three, lateral, three, + diagonal, + // next stride + three, lateral, three, + diagonal, + three, lateral, three, + diagonal, + }; + auto phase_contacts = + { + bB_, bb_, Bb_, + Pb_, + PB_, PP_, BP_, + bP_, + // next stride + bB_, bb_, Bb_, + Pb_, + PB_, PP_, BP_, + bP_, + }; + + return std::make_pair(times, phase_contacts); +} + +QuadrupedGaitGenerator::GaiInfo +QuadrupedGaitGenerator::GetDurationsTrot () const { double t_phase = 0.4; - double t_trans = 0.05; - phase_times_ = + double t_trans = 0.2; + auto times = { - 0.3, t_phase, t_trans, t_phase, t_trans, t_phase, t_trans, t_phase, t_trans, t_phase, t_trans, t_phase, t_trans, - 0.2, }; - phase_contacts_ = + auto phase_contacts = { - BB_, bP_, BB_, Pb_, BB_, bP_, BB_, Pb_, BB_, bP_, BB_, Pb_, BB_, - BB_, }; + + return std::make_pair(times, phase_contacts); } -void -QuadrupedGaitGenerator::SetDurationsTrotFly () +QuadrupedGaitGenerator::GaiInfo +QuadrupedGaitGenerator::GetDurationsTrotFly () const { - double t_phase = 0.4; - double t_trans = 0.05; - phase_times_ = + double stance = 0.3; + double flight = 0.05; + auto times = { - 0.3, - t_phase, t_trans, t_phase, t_trans, - t_phase, t_trans, t_phase, t_trans, - t_phase, t_trans, t_phase, t_trans, - 0.2, + stance, flight, stance, flight, + stance, flight, stance, flight, + stance, flight, stance, flight, }; - phase_contacts_ = + auto phase_contacts = { - BB_, bP_, II_, Pb_, II_, bP_, II_, Pb_, II_, bP_, II_, Pb_, II_, - BB_, }; + + return std::make_pair(times, phase_contacts); } -void -QuadrupedGaitGenerator::SetDurationsPace () +QuadrupedGaitGenerator::GaiInfo +QuadrupedGaitGenerator::GetDurationsPace () const { - double A = 0.4; - double B = 0.1; - phase_times_ = + double A = 0.3; + double B = 0.05; + auto times = { - 0.3, A, B, A, B, A, B, A, B, A, B, A, B, - 0.2, }; - phase_contacts_ = + auto phase_contacts = { - BB_, - PP_, BB_, bb_, BB_, - PP_, BB_, bb_, BB_, - PP_, BB_, bb_, BB_, - BB_, + PP_, II_, bb_, II_, + PP_, II_, bb_, II_, + PP_, II_, bb_, II_, }; + + return std::make_pair(times, phase_contacts); } -void -QuadrupedGaitGenerator::SetDurationsBound () +QuadrupedGaitGenerator::GaiInfo +QuadrupedGaitGenerator::GetDurationsBound () const { - double A = 0.4; - double B = 0.2; - phase_times_ = + double A = 0.3; + double B = 0.05; + auto times = { - 0.3, A, B, A, B, A, B, A, B, A, B, A, B, - 0.2, }; - phase_contacts_ = + auto phase_contacts = { - BB_, - BI_, BB_, IB_, BB_, - BI_, BB_, IB_, BB_, - BI_, BB_, IB_, BB_, - BB_, + BI_, II_, IB_, II_, + BI_, II_, IB_, II_, + BI_, II_, IB_, II_, }; + + return std::make_pair(times, phase_contacts); } QuadrupedGaitGenerator::~QuadrupedGaitGenerator () diff --git a/src/range_of_motion_constraint.cc b/src/range_of_motion_constraint.cc index 5d2ca96be..3ba7854d0 100644 --- a/src/range_of_motion_constraint.cc +++ b/src/range_of_motion_constraint.cc @@ -63,7 +63,7 @@ void RangeOfMotionBox::UpdateBoundsAtInstance (double t, int k, VecBound& bounds) const { for (int dim=0; dim #include -#include #include +#include namespace xpp { diff --git a/src/soft_constraint.cc b/src/soft_constraint.cc index 8c6140430..79d79ddd2 100644 --- a/src/soft_constraint.cc +++ b/src/soft_constraint.cc @@ -10,7 +10,7 @@ #include #include -#include +#include namespace xpp { namespace opt { diff --git a/src/spline_constraint.cc b/src/spline_constraint.cc index b066eb75a..919d2a453 100644 --- a/src/spline_constraint.cc +++ b/src/spline_constraint.cc @@ -9,8 +9,8 @@ #include #include +#include -#include #include namespace xpp { @@ -103,7 +103,7 @@ SplineStateConstraint::GetBounds () const for (auto dxdt : derivatives_) { VectorXd state = state_desired_.GetByIndex(dxdt); for (auto dim : dims_) - bounds.push_back(Bound(state(dim), state(dim))); + bounds.push_back(NLPBound(state(dim), state(dim))); } return bounds; diff --git a/src/terrain_constraint.cc b/src/terrain_constraint.cc index c181aa516..6c30c8b63 100644 --- a/src/terrain_constraint.cc +++ b/src/terrain_constraint.cc @@ -58,7 +58,7 @@ TerrainConstraint::GetBounds () const if (ee_motion_->IsContactNode(i)) bounds.at(i) = BoundZero; else - bounds.at(i) = Bound(0.0, max_z_distance_above_terrain_); + bounds.at(i) = NLPBound(0.0, max_z_distance_above_terrain_); } return bounds; diff --git a/src/time_discretization_constraint.cc b/src/time_discretization_constraint.cc index 4719a05ac..8fe8f4e30 100644 --- a/src/time_discretization_constraint.cc +++ b/src/time_discretization_constraint.cc @@ -11,7 +11,7 @@ #include #include -#include +#include namespace xpp { namespace opt {