phase_nodes.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/variables/phase_nodes.h>
00031 #include <towr/variables/cartesian_dimensions.h>
00032 
00033 namespace towr {
00034 
00035 std::vector<PhaseNodes::PolyInfo>
00036 BuildPolyInfos (int phase_count, bool is_in_contact_at_start,
00037                 int n_polys_in_changing_phase, PhaseNodes::Type type)
00038 {
00039   using PolyInfo = PhaseNodes::PolyInfo;
00040   std::vector<PolyInfo> polynomial_info;
00041 
00042   bool first_phase_constant = (is_in_contact_at_start  && type==PhaseNodes::Motion)
00043                            || (!is_in_contact_at_start && type==PhaseNodes::Force);
00044 
00045 
00046   bool phase_constant = first_phase_constant;
00047 
00048   for (int i=0; i<phase_count; ++i) {
00049     if (phase_constant)
00050       polynomial_info.push_back(PolyInfo(i,0,1, true));
00051     else
00052       for (int j=0; j<n_polys_in_changing_phase; ++j)
00053         polynomial_info.push_back(PolyInfo(i,j,n_polys_in_changing_phase, false));
00054 
00055     phase_constant = !phase_constant; // constant and non-constant phase alternate
00056   }
00057 
00058   return polynomial_info;
00059 }
00060 
00061 PhaseNodes::PhaseNodes (int phase_count,
00062                         bool is_in_contact_at_start,
00063                         const std::string& name,
00064                         int n_polys_in_changing_phase,
00065                         Type type)
00066     :Nodes(3, name)
00067 {
00068   polynomial_info_ = BuildPolyInfos(phase_count, is_in_contact_at_start, n_polys_in_changing_phase, type);
00069   optnode_to_node_ = GetOptNodeToNodeMappings(polynomial_info_);
00070 
00071   int n_opt_variables = optnode_to_node_.size() * 2*GetDim();
00072   int n_nodes = polynomial_info_.size()+1;
00073   InitMembers(n_nodes, n_opt_variables);
00074 
00075   if (type == Motion)
00076     SetBoundsEEMotion();
00077   else if (type == Force)
00078     SetBoundsEEForce();
00079   else
00080     assert(false); // phase-node type not defined
00081 }
00082 
00083 PhaseNodes::VecDurations
00084 PhaseNodes::ConvertPhaseToPolyDurations(const VecDurations& phase_durations) const
00085 {
00086   VecDurations poly_durations;
00087 
00088   for (int i=0; i<GetPolynomialCount(); ++i) {
00089     auto info = polynomial_info_.at(i);
00090     poly_durations.push_back(phase_durations.at(info.phase_)/info.n_polys_in_phase_);
00091   }
00092 
00093   return poly_durations;
00094 }
00095 
00096 double
00097 PhaseNodes::GetDerivativeOfPolyDurationWrtPhaseDuration (int poly_id) const
00098 {
00099   int n_polys_in_phase = polynomial_info_.at(poly_id).n_polys_in_phase_;
00100   return 1./n_polys_in_phase;
00101 }
00102 
00103 int
00104 PhaseNodes::GetNumberOfPrevPolynomialsInPhase(int poly_id) const
00105 {
00106   return polynomial_info_.at(poly_id).poly_in_phase_;
00107 }
00108 
00109 std::map<PhaseNodes::OptNodeIs, PhaseNodes::NodeIds>
00110 PhaseNodes::GetOptNodeToNodeMappings (const std::vector<PolyInfo>& polynomial_info)
00111 {
00112   std::map<OptNodeIs, NodeIds> optnode_to_node;
00113 
00114   int opt_id = 0;
00115   for (int i=0; i<polynomial_info.size(); ++i) {
00116     int node_id_start = GetNodeId(i, Side::Start);
00117 
00118     optnode_to_node[opt_id].push_back(node_id_start);
00119     // use same value for next node if polynomial is constant
00120     if (!polynomial_info.at(i).is_constant_)
00121       opt_id++;
00122   }
00123 
00124   int last_node_id = polynomial_info.size();
00125   optnode_to_node[opt_id].push_back(last_node_id);
00126 
00127   return optnode_to_node;
00128 }
00129 
00130 std::vector<PhaseNodes::IndexInfo>
00131 PhaseNodes::GetNodeInfoAtOptIndex(int idx) const
00132 {
00133   std::vector<IndexInfo> nodes;
00134 
00135   // always two consecutive node pairs are equal
00136   int n_opt_values_per_node_ = 2*GetDim();
00137   int internal_id = idx%n_opt_values_per_node_; // 0...6 (p.x, p.y, p.z, v.x, v.y. v.z)
00138 
00139   IndexInfo node;
00140   node.node_deriv_     = internal_id<GetDim()? kPos : kVel;
00141   node.node_dim_ = internal_id%GetDim();
00142 
00143   // this is different compared to standard node values
00144   // because one index can represent multiple node (during constant phase)
00145   int opt_node = std::floor(idx/n_opt_values_per_node_);
00146   for (auto node_id : optnode_to_node_.at(opt_node)) {
00147     node.node_id_ = node_id;
00148     nodes.push_back(node);
00149   }
00150 
00151   return nodes;
00152 }
00153 
00154 bool
00155 PhaseNodes::IsConstantNode (int node_id) const
00156 {
00157   bool is_constant = false;
00158 
00159   // node is considered constant if either left or right polynomial
00160   // belongs to a constant phase
00161   for (int poly_id : GetAdjacentPolyIds(node_id))
00162     if (IsInConstantPhase(poly_id))
00163       is_constant = true;
00164 
00165   return is_constant;
00166 }
00167 
00168 bool
00169 PhaseNodes::IsInConstantPhase(int poly_id) const
00170 {
00171   return polynomial_info_.at(poly_id).is_constant_;
00172 }
00173 
00174 PhaseNodes::NodeIds
00175 PhaseNodes::GetIndicesOfNonConstantNodes() const
00176 {
00177   NodeIds node_ids;
00178 
00179   for (int id=0; id<GetNodes().size(); ++id)
00180     if (!IsConstantNode(id))
00181       node_ids.push_back(id);
00182 
00183   return node_ids;
00184 }
00185 
00186 int
00187 PhaseNodes::GetPhase (int node_id) const
00188 {
00189   assert(!IsConstantNode(node_id)); // because otherwise it has two phases
00190 
00191   int poly_id = GetAdjacentPolyIds(node_id).front();
00192   return polynomial_info_.at(poly_id).phase_;
00193 }
00194 
00195 int
00196 PhaseNodes::GetPolyIDAtStartOfPhase (int phase) const
00197 {
00198   int poly_id=0;
00199   for (int i=0; i<polynomial_info_.size(); ++i)
00200     if (polynomial_info_.at(i).phase_ == phase)
00201       return i;
00202 }
00203 
00204 Eigen::Vector3d
00205 PhaseNodes::GetValueAtStartOfPhase (int phase) const
00206 {
00207   int node_id = GetNodeIDAtStartOfPhase(phase);
00208   return GetNodes().at(node_id).p();
00209 }
00210 
00211 int
00212 PhaseNodes::GetNodeIDAtStartOfPhase (int phase) const
00213 {
00214   int poly_id=GetPolyIDAtStartOfPhase(phase);
00215   return GetNodeId(poly_id, Side::Start);
00216 }
00217 
00218 std::vector<int>
00219 PhaseNodes::GetAdjacentPolyIds (int node_id) const
00220 {
00221   std::vector<int> poly_ids;
00222   int last_node_id = GetNodes().size()-1;
00223 
00224   if (node_id==0)
00225     poly_ids.push_back(0);
00226   else if (node_id==last_node_id)
00227     poly_ids.push_back(last_node_id-1);
00228   else {
00229     poly_ids.push_back(node_id-1);
00230     poly_ids.push_back(node_id);
00231   }
00232 
00233   return poly_ids;
00234 }
00235 
00236 void
00237 PhaseNodes::SetBoundsEEMotion ()
00238 {
00239   for (int i=0; i<GetRows(); ++i) {
00240 
00241     auto idx = GetNodeInfoAtOptIndex(i).front(); // bound idx by first node it represents
00242 
00243     // stance node
00244     if (IsConstantNode(idx.node_id_)) {
00245 
00246       // endeffector is not allowed to move if in stance phase
00247       if (idx.node_deriv_ == kVel)
00248         bounds_.at(i) = ifopt::BoundZero;
00249 
00250     // swing node
00251     } else {
00252 
00253       // zero velocity at top
00254       if (idx.node_deriv_ == kVel && idx.node_dim_ == Z)
00255         bounds_.at(i) = ifopt::BoundZero;
00256 
00257       /*
00258       // to not have really fast swing motions
00259       if (idx.node_deriv_ == kVel)
00260         bounds_.at(i) = ifopt::Bounds(-5.0, 5.0); // zero velocity at top
00261       */
00262     }
00263   }
00264 }
00265 
00266 void
00267 PhaseNodes::SetBoundsEEForce ()
00268 {
00269   for (int i=0; i<GetRows(); ++i) {
00270 
00271     IndexInfo idx = GetNodeInfoAtOptIndex(i).front(); // only one node anyway
00272 
00273     // stance node
00274     if (!IsConstantNode(idx.node_id_)) {
00275 
00276       /*
00277       // zero slope to never exceed zero force between nodes
00278       if (idx.node_deriv_ == kVel) {
00279         bounds_.at(i) = ifopt::BoundZero;
00280       }
00281       */
00282 
00283     // swing node
00284     } else {
00285       bounds_.at(i) = ifopt::BoundZero; // force must be zero
00286     }
00287 
00288   }
00289 }
00290 
00291 PhaseNodes::PolyInfo::PolyInfo(int phase, int poly_id_in_phase,
00292                                int num_polys_in_phase, bool is_constant)
00293     :phase_(phase),
00294      poly_in_phase_(poly_id_in_phase),
00295      n_polys_in_phase_(num_polys_in_phase),
00296      is_constant_(is_constant)
00297 {
00298 }
00299 
00300 } /* namespace towr */


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