nlp_factory.cc
Go to the documentation of this file.
00001 /******************************************************************************
00002 Copyright (c) 2018, Alexander W. Winkler. All rights reserved.
00003 
00004 Redistribution and use in source and binary forms, with or without
00005 modification, are permitted provided that the following conditions are met:
00006 
00007 * Redistributions of source code must retain the above copyright notice, this
00008   list of conditions and the following disclaimer.
00009 
00010 * Redistributions in binary form must reproduce the above copyright notice,
00011   this list of conditions and the following disclaimer in the documentation
00012   and/or other materials provided with the distribution.
00013 
00014 * Neither the name of the copyright holder nor the names of its
00015   contributors may be used to endorse or promote products derived from
00016   this software without specific prior written permission.
00017 
00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00021 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
00022 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00023 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00024 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00025 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
00026 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00027 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00028 ******************************************************************************/
00029 
00030 #include <towr/nlp_factory.h>
00031 
00032 #include <towr/variables/variable_names.h>
00033 #include <towr/variables/base_nodes.h>
00034 #include <towr/variables/phase_durations.h>
00035 
00036 #include <towr/constraints/base_motion_constraint.h>
00037 #include <towr/constraints/dynamic_constraint.h>
00038 #include <towr/constraints/force_constraint.h>
00039 #include <towr/constraints/range_of_motion_constraint.h>
00040 #include <towr/constraints/swing_constraint.h>
00041 #include <towr/constraints/terrain_constraint.h>
00042 #include <towr/constraints/total_duration_constraint.h>
00043 #include <towr/constraints/spline_acc_constraint.h>
00044 
00045 #include <towr/costs/node_cost.h>
00046 
00047 namespace towr {
00048 
00049 
00050 NlpFactory::VariablePtrVec
00051 NlpFactory::GetVariableSets ()
00052 {
00053   VariablePtrVec vars;
00054 
00055   auto base_motion = MakeBaseVariables();
00056   vars.insert(vars.end(), base_motion.begin(), base_motion.end());
00057 
00058   auto ee_motion = MakeEndeffectorVariables();
00059   vars.insert(vars.end(), ee_motion.begin(), ee_motion.end());
00060 
00061   auto ee_force = MakeForceVariables();
00062   vars.insert(vars.end(), ee_force.begin(), ee_force.end());
00063 
00064   auto contact_schedule = MakeContactScheduleVariables();
00065   if (params_.OptimizeTimings()) {
00066     vars.insert(vars.end(), contact_schedule.begin(), contact_schedule.end());
00067   }
00068 
00069   // stores these readily constructed spline, independent of whether the
00070   // nodes and durations these depend on are optimized over
00071   spline_holder_ = SplineHolder(base_motion.at(0), // linear
00072                                 base_motion.at(1), // angular
00073                                 params_.GetBasePolyDurations(),
00074                                 ee_motion,
00075                                 ee_force,
00076                                 contact_schedule,
00077                                 params_.OptimizeTimings());
00078   return vars;
00079 }
00080 
00081 std::vector<Nodes::Ptr>
00082 NlpFactory::MakeBaseVariables () const
00083 {
00084   std::vector<Nodes::Ptr> vars;
00085 
00086   int n_nodes = params_.GetBasePolyDurations().size() + 1;
00087 
00088   auto spline_lin = std::make_shared<BaseNodes>(n_nodes, id::base_lin_nodes);
00089   spline_lin->InitializeNodesTowardsGoal(initial_base_.lin.p(), final_base_.lin.p(), params_.t_total_);
00090   spline_lin->AddStartBound(kPos, {X,Y,Z}, initial_base_.lin.p());
00091   spline_lin->AddStartBound(kVel, {X,Y,Z}, initial_base_.lin.v());
00092   spline_lin->AddFinalBound(kPos, {X,Y}  , final_base_.lin.p());
00093   spline_lin->AddFinalBound(kVel, {X,Y,Z}, final_base_.lin.v());
00094   vars.push_back(spline_lin);
00095 
00096   auto spline_ang = std::make_shared<BaseNodes>(n_nodes,  id::base_ang_nodes);
00097   spline_ang->InitializeNodesTowardsGoal(initial_base_.ang.p(), final_base_.ang.p(), params_.t_total_);
00098   spline_ang->AddStartBound(kPos, {X,Y,Z}, initial_base_.ang.p());
00099   spline_ang->AddStartBound(kVel, {X,Y,Z}, initial_base_.ang.v());
00100   spline_ang->AddFinalBound(kPos,     {Z}, final_base_.ang.p());
00101   spline_ang->AddFinalBound(kVel, {X,Y,Z}, final_base_.ang.v());
00102   vars.push_back(spline_ang);
00103 
00104   return vars;
00105 }
00106 
00107 std::vector<PhaseNodes::Ptr>
00108 NlpFactory::MakeEndeffectorVariables () const
00109 {
00110   std::vector<PhaseNodes::Ptr> vars;
00111 
00112   // Endeffector Motions
00113   double T = params_.t_total_;
00114   for (int ee=0; ee<params_.GetEECount(); ee++) {
00115 
00116     auto nodes = std::make_shared<PhaseNodes>(params_.GetPhaseCount(ee),
00117                                               params_.ee_in_contact_at_start_.at(ee),
00118                                               id::EEMotionNodes(ee),
00119                                               params_.ee_polynomials_per_swing_phase_,
00120                                               PhaseNodes::Motion);
00121 
00122     double yaw = final_base_.ang.p().z();
00123 
00124     // smell adapt to desired yaw state
00125 //    Eigen::Matrix3d w_R_b = GetQuaternionFromEulerZYX(yaw, 0.0, 0.0).toRotationMatrix();
00126     Eigen::Matrix3d w_R_b; w_R_b.setIdentity();
00127 
00128     Vector3d final_ee_pos_W = final_base_.lin.p() + w_R_b*model_.kinematic_model_->GetNominalStanceInBase().at(ee);
00129 
00130 
00131 
00132     nodes->InitializeNodesTowardsGoal(initial_ee_W_.at(ee), final_ee_pos_W, T);
00133 
00134     // actually initial Z position should be constrained as well...-.-
00135     nodes->AddStartBound(kPos, {X,Y}, initial_ee_W_.at(ee));
00136 
00137     // fix final endeffector position
00138 //    bool step_taken = nodes->GetNodes().size() > 2;
00139 //    if (step_taken) // otherwise overwrites start bound
00140 //      nodes->AddFinalBound(kPos, {X,Y}, final_ee_pos_W);
00141 
00142     vars.push_back(nodes);
00143   }
00144 
00145 
00146   return vars;
00147 }
00148 
00149 std::vector<PhaseNodes::Ptr>
00150 NlpFactory::MakeForceVariables () const
00151 {
00152   std::vector<PhaseNodes::Ptr> vars;
00153 
00154   double T = params_.t_total_;
00155   for (int ee=0; ee<params_.GetEECount(); ee++) {
00156 
00157     auto nodes = std::make_shared<PhaseNodes>(params_.GetPhaseCount(ee),
00158                                               params_.ee_in_contact_at_start_.at(ee),
00159                                               id::EEForceNodes(ee),
00160                                               params_.force_polynomials_per_stance_phase_,
00161                                               PhaseNodes::Force);
00162 
00163     // initialize with mass of robot distributed equally on all legs
00164     double m = model_.dynamic_model_->m();
00165     double g = model_.dynamic_model_->g();
00166 
00167 
00168     Vector3d f_stance(0.0, 0.0, m*g/params_.GetEECount());
00169     nodes->InitializeNodesTowardsGoal(f_stance, f_stance, T);
00170     vars.push_back(nodes);
00171   }
00172 
00173   return vars;
00174 }
00175 
00176 std::vector<PhaseDurations::Ptr>
00177 NlpFactory::MakeContactScheduleVariables () const
00178 {
00179   std::vector<PhaseDurations::Ptr> vars;
00180 
00181   for (int ee=0; ee<params_.GetEECount(); ee++) {
00182 
00183     auto var = std::make_shared<PhaseDurations>(ee,
00184                                                 params_.ee_phase_durations_.at(ee),
00185                                                 params_.ee_in_contact_at_start_.at(ee),
00186                                                 params_.min_phase_duration_,
00187                                                 params_.max_phase_duration_);
00188     vars.push_back(var);
00189   }
00190 
00191   return vars;
00192 }
00193 
00194 NlpFactory::ContraintPtrVec
00195 NlpFactory::GetConstraints() const
00196 {
00197   ContraintPtrVec constraints;
00198   for (ConstraintName name : params_.constraints_)
00199     for (auto c : GetConstraint(name))
00200       constraints.push_back(c);
00201 
00202   return constraints;
00203 }
00204 
00205 NlpFactory::ContraintPtrVec
00206 NlpFactory::GetConstraint (ConstraintName name) const
00207 {
00208   switch (name) {
00209     case Dynamic:        return MakeDynamicConstraint();
00210     case EndeffectorRom: return MakeRangeOfMotionBoxConstraint();
00211     case BaseRom:        return MakeBaseRangeOfMotionConstraint();
00212     case TotalTime:      return MakeTotalTimeConstraint();
00213     case Terrain:        return MakeTerrainConstraint();
00214     case Force:          return MakeForceConstraint();
00215     case Swing:          return MakeSwingConstraint();
00216     case BaseAcc:        return MakeBaseAccConstraint();
00217     default: throw std::runtime_error("constraint not defined!");
00218   }
00219 }
00220 
00221 
00222 NlpFactory::ContraintPtrVec
00223 NlpFactory::MakeBaseRangeOfMotionConstraint () const
00224 {
00225   return {std::make_shared<BaseMotionConstraint>(params_, spline_holder_)};
00226 }
00227 
00228 NlpFactory::ContraintPtrVec
00229 NlpFactory::MakeDynamicConstraint() const
00230 {
00231   auto constraint = std::make_shared<DynamicConstraint>(model_.dynamic_model_,
00232                                                         params_,
00233                                                         spline_holder_);
00234   return {constraint};
00235 }
00236 
00237 NlpFactory::ContraintPtrVec
00238 NlpFactory::MakeRangeOfMotionBoxConstraint () const
00239 {
00240   ContraintPtrVec c;
00241 
00242   for (int ee=0; ee<params_.GetEECount(); ee++) {
00243     auto rom_constraints = std::make_shared<RangeOfMotionConstraint>(model_.kinematic_model_,
00244                                                               params_,
00245                                                               ee,
00246                                                               spline_holder_);
00247     c.push_back(rom_constraints);
00248   }
00249 
00250   return c;
00251 }
00252 
00253 NlpFactory::ContraintPtrVec
00254 NlpFactory::MakeTotalTimeConstraint () const
00255 {
00256   ContraintPtrVec c;
00257   double T = params_.t_total_;
00258 
00259   for (int ee=0; ee<params_.GetEECount(); ee++) {
00260     auto duration_constraint = std::make_shared<TotalDurationConstraint>(T, ee);
00261     c.push_back(duration_constraint);
00262   }
00263 
00264   return c;
00265 }
00266 
00267 NlpFactory::ContraintPtrVec
00268 NlpFactory::MakeTerrainConstraint () const
00269 {
00270   ContraintPtrVec constraints;
00271 
00272   for (int ee=0; ee<params_.GetEECount(); ee++) {
00273     auto c = std::make_shared<TerrainConstraint>(terrain_, id::EEMotionNodes(ee));
00274     constraints.push_back(c);
00275   }
00276 
00277   return constraints;
00278 }
00279 
00280 NlpFactory::ContraintPtrVec
00281 NlpFactory::MakeForceConstraint () const
00282 {
00283   ContraintPtrVec constraints;
00284 
00285   for (int ee=0; ee<params_.GetEECount(); ee++) {
00286     auto c = std::make_shared<ForceConstraint>(terrain_,
00287                                                params_.force_limit_in_norm_,
00288                                                ee);
00289     constraints.push_back(c);
00290   }
00291 
00292   return constraints;
00293 }
00294 
00295 NlpFactory::ContraintPtrVec
00296 NlpFactory::MakeSwingConstraint () const
00297 {
00298   ContraintPtrVec constraints;
00299 
00300   for (int ee=0; ee<params_.GetEECount(); ee++) {
00301     auto swing = std::make_shared<SwingConstraint>(id::EEMotionNodes(ee));
00302     constraints.push_back(swing);
00303   }
00304 
00305   return constraints;
00306 }
00307 
00308 NlpFactory::ContraintPtrVec
00309 NlpFactory::MakeBaseAccConstraint () const
00310 {
00311   ContraintPtrVec constraints;
00312 
00313   constraints.push_back(std::make_shared<SplineAccConstraint>
00314                         (spline_holder_.base_linear_, id::base_lin_nodes));
00315 
00316   constraints.push_back(std::make_shared<SplineAccConstraint>
00317                         (spline_holder_.base_angular_, id::base_ang_nodes));
00318 
00319   return constraints;
00320 }
00321 
00322 NlpFactory::ContraintPtrVec
00323 NlpFactory::GetCosts() const
00324 {
00325   ContraintPtrVec costs;
00326   for (const auto& pair : params_.costs_)
00327     for (auto c : GetCost(pair.first, pair.second))
00328       costs.push_back(c);
00329 
00330   return costs;
00331 }
00332 
00333 NlpFactory::CostPtrVec
00334 NlpFactory::GetCost(const CostName& name, double weight) const
00335 {
00336   switch (name) {
00337     case ForcesCostID:       return MakeForcesCost(weight);
00338     default: throw std::runtime_error("cost not defined!");
00339   }
00340 }
00341 
00342 NlpFactory::CostPtrVec
00343 NlpFactory::MakeForcesCost(double weight) const
00344 {
00345   CostPtrVec cost;
00346 
00347   for (int ee=0; ee<params_.GetEECount(); ee++)
00348     cost.push_back(std::make_shared<NodeCost>(id::EEForceNodes(ee), kPos, Z));
00349 
00350   return cost;
00351 }
00352 
00353 } /* namespace towr */


towr_core
Author(s): Alexander W. Winkler
autogenerated on Mon Apr 9 2018 03:12:44