phase_nodes.cc
Go to the documentation of this file.
1 /******************************************************************************
2 Copyright (c) 2018, Alexander W. Winkler. All rights reserved.
3 
4 Redistribution and use in source and binary forms, with or without
5 modification, are permitted provided that the following conditions are met:
6 
7 * Redistributions of source code must retain the above copyright notice, this
8  list of conditions and the following disclaimer.
9 
10 * Redistributions in binary form must reproduce the above copyright notice,
11  this list of conditions and the following disclaimer in the documentation
12  and/or other materials provided with the distribution.
13 
14 * Neither the name of the copyright holder nor the names of its
15  contributors may be used to endorse or promote products derived from
16  this software without specific prior written permission.
17 
18 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
19 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
20 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
21 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
22 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
23 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
24 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
25 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
26 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
27 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
28 ******************************************************************************/
29 
32 
33 namespace towr {
34 
35 std::vector<PhaseNodes::PolyInfo>
36 BuildPolyInfos (int phase_count, bool is_in_contact_at_start,
37  int n_polys_in_changing_phase, PhaseNodes::Type type)
38 {
39  using PolyInfo = PhaseNodes::PolyInfo;
40  std::vector<PolyInfo> polynomial_info;
41 
42  bool first_phase_constant = (is_in_contact_at_start && type==PhaseNodes::Motion)
43  || (!is_in_contact_at_start && type==PhaseNodes::Force);
44 
45 
46  bool phase_constant = first_phase_constant;
47 
48  for (int i=0; i<phase_count; ++i) {
49  if (phase_constant)
50  polynomial_info.push_back(PolyInfo(i,0,1, true));
51  else
52  for (int j=0; j<n_polys_in_changing_phase; ++j)
53  polynomial_info.push_back(PolyInfo(i,j,n_polys_in_changing_phase, false));
54 
55  phase_constant = !phase_constant; // constant and non-constant phase alternate
56  }
57 
58  return polynomial_info;
59 }
60 
61 PhaseNodes::PhaseNodes (int phase_count,
62  bool is_in_contact_at_start,
63  const std::string& name,
64  int n_polys_in_changing_phase,
65  Type type)
66  :Nodes(3, name)
67 {
68  polynomial_info_ = BuildPolyInfos(phase_count, is_in_contact_at_start, n_polys_in_changing_phase, type);
70 
71  int n_opt_variables = optnode_to_node_.size() * 2*GetDim();
72  int n_nodes = polynomial_info_.size()+1;
73  InitMembers(n_nodes, n_opt_variables);
74 
75  if (type == Motion)
77  else if (type == Force)
79  else
80  assert(false); // phase-node type not defined
81 }
82 
85 {
86  VecDurations poly_durations;
87 
88  for (int i=0; i<GetPolynomialCount(); ++i) {
89  auto info = polynomial_info_.at(i);
90  poly_durations.push_back(phase_durations.at(info.phase_)/info.n_polys_in_phase_);
91  }
92 
93  return poly_durations;
94 }
95 
96 double
98 {
99  int n_polys_in_phase = polynomial_info_.at(poly_id).n_polys_in_phase_;
100  return 1./n_polys_in_phase;
101 }
102 
103 int
105 {
106  return polynomial_info_.at(poly_id).poly_in_phase_;
107 }
108 
109 std::map<PhaseNodes::OptNodeIs, PhaseNodes::NodeIds>
110 PhaseNodes::GetOptNodeToNodeMappings (const std::vector<PolyInfo>& polynomial_info)
111 {
112  std::map<OptNodeIs, NodeIds> optnode_to_node;
113 
114  int opt_id = 0;
115  for (int i=0; i<polynomial_info.size(); ++i) {
116  int node_id_start = GetNodeId(i, Side::Start);
117 
118  optnode_to_node[opt_id].push_back(node_id_start);
119  // use same value for next node if polynomial is constant
120  if (!polynomial_info.at(i).is_constant_)
121  opt_id++;
122  }
123 
124  int last_node_id = polynomial_info.size();
125  optnode_to_node[opt_id].push_back(last_node_id);
126 
127  return optnode_to_node;
128 }
129 
130 std::vector<PhaseNodes::IndexInfo>
132 {
133  std::vector<IndexInfo> nodes;
134 
135  // always two consecutive node pairs are equal
136  int n_opt_values_per_node_ = 2*GetDim();
137  int internal_id = idx%n_opt_values_per_node_; // 0...6 (p.x, p.y, p.z, v.x, v.y. v.z)
138 
139  IndexInfo node;
140  node.node_deriv_ = internal_id<GetDim()? kPos : kVel;
141  node.node_dim_ = internal_id%GetDim();
142 
143  // this is different compared to standard node values
144  // because one index can represent multiple node (during constant phase)
145  int opt_node = std::floor(idx/n_opt_values_per_node_);
146  for (auto node_id : optnode_to_node_.at(opt_node)) {
147  node.node_id_ = node_id;
148  nodes.push_back(node);
149  }
150 
151  return nodes;
152 }
153 
154 bool
155 PhaseNodes::IsConstantNode (int node_id) const
156 {
157  bool is_constant = false;
158 
159  // node is considered constant if either left or right polynomial
160  // belongs to a constant phase
161  for (int poly_id : GetAdjacentPolyIds(node_id))
162  if (IsInConstantPhase(poly_id))
163  is_constant = true;
164 
165  return is_constant;
166 }
167 
168 bool
170 {
171  return polynomial_info_.at(poly_id).is_constant_;
172 }
173 
176 {
177  NodeIds node_ids;
178 
179  for (int id=0; id<GetNodes().size(); ++id)
180  if (!IsConstantNode(id))
181  node_ids.push_back(id);
182 
183  return node_ids;
184 }
185 
186 int
187 PhaseNodes::GetPhase (int node_id) const
188 {
189  assert(!IsConstantNode(node_id)); // because otherwise it has two phases
190 
191  int poly_id = GetAdjacentPolyIds(node_id).front();
192  return polynomial_info_.at(poly_id).phase_;
193 }
194 
195 int
197 {
198  int poly_id=0;
199  for (int i=0; i<polynomial_info_.size(); ++i)
200  if (polynomial_info_.at(i).phase_ == phase)
201  return i;
202 }
203 
204 Eigen::Vector3d
206 {
207  int node_id = GetNodeIDAtStartOfPhase(phase);
208  return GetNodes().at(node_id).p();
209 }
210 
211 int
213 {
214  int poly_id=GetPolyIDAtStartOfPhase(phase);
215  return GetNodeId(poly_id, Side::Start);
216 }
217 
218 std::vector<int>
220 {
221  std::vector<int> poly_ids;
222  int last_node_id = GetNodes().size()-1;
223 
224  if (node_id==0)
225  poly_ids.push_back(0);
226  else if (node_id==last_node_id)
227  poly_ids.push_back(last_node_id-1);
228  else {
229  poly_ids.push_back(node_id-1);
230  poly_ids.push_back(node_id);
231  }
232 
233  return poly_ids;
234 }
235 
236 void
238 {
239  for (int i=0; i<GetRows(); ++i) {
240 
241  auto idx = GetNodeInfoAtOptIndex(i).front(); // bound idx by first node it represents
242 
243  // stance node
244  if (IsConstantNode(idx.node_id_)) {
245 
246  // endeffector is not allowed to move if in stance phase
247  if (idx.node_deriv_ == kVel)
248  bounds_.at(i) = ifopt::BoundZero;
249 
250  // swing node
251  } else {
252 
253  // zero velocity at top
254  if (idx.node_deriv_ == kVel && idx.node_dim_ == Z)
255  bounds_.at(i) = ifopt::BoundZero;
256 
257  /*
258  // to not have really fast swing motions
259  if (idx.node_deriv_ == kVel)
260  bounds_.at(i) = ifopt::Bounds(-5.0, 5.0); // zero velocity at top
261  */
262  }
263  }
264 }
265 
266 void
268 {
269  for (int i=0; i<GetRows(); ++i) {
270 
271  IndexInfo idx = GetNodeInfoAtOptIndex(i).front(); // only one node anyway
272 
273  // stance node
274  if (!IsConstantNode(idx.node_id_)) {
275 
276  /*
277  // zero slope to never exceed zero force between nodes
278  if (idx.node_deriv_ == kVel) {
279  bounds_.at(i) = ifopt::BoundZero;
280  }
281  */
282 
283  // swing node
284  } else {
285  bounds_.at(i) = ifopt::BoundZero; // force must be zero
286  }
287 
288  }
289 }
290 
291 PhaseNodes::PolyInfo::PolyInfo(int phase, int poly_id_in_phase,
292  int num_polys_in_phase, bool is_constant)
293  :phase_(phase),
294  poly_in_phase_(poly_id_in_phase),
295  n_polys_in_phase_(num_polys_in_phase),
296  is_constant_(is_constant)
297 {
298 }
299 
300 } /* namespace towr */
virtual bool IsInConstantPhase(int polynomial_id) const
Is the polynomial constant, so not changing the value.
Definition: phase_nodes.cc:169
virtual VecDurations ConvertPhaseToPolyDurations(const VecDurations &phase_durations) const
Converts durations of swing and stance phases to polynomial durations.
Definition: phase_nodes.cc:84
void SetBoundsEEMotion()
Sets the bounds on the node variables to model foot motions.
Definition: phase_nodes.cc:237
NodeIds GetIndicesOfNonConstantNodes() const
The indices of those nodes that don&#39;t belong to a constant phase.
Definition: phase_nodes.cc:175
static std::map< OptNodeIs, NodeIds > GetOptNodeToNodeMappings(const std::vector< PolyInfo > &)
Definition: phase_nodes.cc:110
std::map< OptNodeIs, NodeIds > optnode_to_node_
Definition: phase_nodes.h:155
void SetBoundsEEForce()
Sets the bounds on the node variables to model foot forces.
Definition: phase_nodes.cc:267
virtual double GetDerivativeOfPolyDurationWrtPhaseDuration(int polynomial_id) const
How a change in the phase duration affects the polynomial duration.
Definition: phase_nodes.cc:97
Eigen::Vector3d GetValueAtStartOfPhase(int phase) const
Definition: phase_nodes.cc:205
virtual bool IsConstantNode(int node_id) const
node is constant if either left or right polynomial belongs to a constant phase.
Definition: phase_nodes.cc:155
std::vector< double > VecDurations
Definition: nodes.h:55
Holds semantic information each polynomial in spline.
Definition: phase_nodes.h:57
std::vector< PolyInfo > polynomial_info_
Definition: phase_nodes.h:150
std::vector< PhaseNodes::PolyInfo > BuildPolyInfos(int phase_count, bool is_in_contact_at_start, int n_polys_in_changing_phase, PhaseNodes::Type type)
Definition: phase_nodes.cc:36
std::vector< int > NodeIds
Definition: phase_nodes.h:50
int node_dim_
the dimension (x,y,z) of that optimization index.
Definition: nodes.h:64
PhaseNodes(int phase_count, bool in_contact_start, const std::string &var_name, int n_polys_in_changing_phase, Type type)
Constructs a variable set of node variables.
Definition: phase_nodes.cc:61
Position and velocity of nodes used to generate a Hermite spline.
Definition: nodes.h:52
PolyInfo(int phase, int poly_in_phase, int n_polys_in_phase, bool is_const)
Definition: phase_nodes.cc:291
int GetDim() const
Definition: nodes.cc:162
std::vector< int > GetAdjacentPolyIds(int node_id) const
Definition: phase_nodes.cc:219
int GetPolyIDAtStartOfPhase(int phase) const
Definition: phase_nodes.cc:196
void InitMembers(int n_nodes, int n_variables)
initializes the member variables.
Definition: nodes.cc:43
VecBound bounds_
the bounds on the node values.
Definition: nodes.h:176
static int GetNodeId(int poly_id, Side side)
The node ID that belongs to a specific side of a specific polynomial.
Definition: nodes.cc:147
int GetPolynomialCount() const
Definition: nodes.cc:168
Dx node_deriv_
The derivative (pos,vel) of that optimziation index.
Definition: nodes.h:63
Holds information about the node the optimization index represents.
Definition: nodes.h:61
int GetPhase(int node_id) const
Definition: phase_nodes.cc:187
int node_id_
The ID of the node of the optimization index.
Definition: nodes.h:62
int GetNodeIDAtStartOfPhase(int phase) const
Definition: phase_nodes.cc:212
virtual std::vector< IndexInfo > GetNodeInfoAtOptIndex(int idx) const override
The node information that the optimization index represents.
Definition: phase_nodes.cc:131
virtual int GetNumberOfPrevPolynomialsInPhase(int polynomial_id) const
How many polynomials in the current phase come before.
Definition: phase_nodes.cc:104
const std::vector< Node > GetNodes() const
Definition: nodes.cc:180


towr_core
Author(s): Alexander W. Winkler
autogenerated on Sat Apr 7 2018 02:15:57