phase_nodes.h
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 
30 #ifndef TOWR_VARIABLES_PHASE_NODES_H_
31 #define TOWR_VARIABLES_PHASE_NODES_H_
32 
33 #include "nodes.h"
34 
35 namespace towr {
36 
46 class PhaseNodes : public Nodes {
47 public:
48  using Ptr = std::shared_ptr<PhaseNodes>;
49  using OptNodeIs = int;
50  using NodeIds = std::vector<int>;
51 
52  enum Type {Force, Motion};
53 
57  struct PolyInfo {
58  int phase_;
61  bool is_constant_;
62  PolyInfo(int phase, int poly_in_phase, int n_polys_in_phase, bool is_const);
63  };
64 
74  PhaseNodes (int phase_count, bool in_contact_start, const std::string& var_name,
75  int n_polys_in_changing_phase, Type type);
76 
77  virtual ~PhaseNodes() = default;
78 
79  virtual std::vector<IndexInfo> GetNodeInfoAtOptIndex(int idx) const override;
80 
84  Eigen::Vector3d GetValueAtStartOfPhase(int phase) const;
85 
89  int GetNodeIDAtStartOfPhase(int phase) const;
90 
96  int GetPhase(int node_id) const;
97 
102  virtual bool IsConstantNode(int node_id) const;
103 
111 
118  virtual VecDurations
119  ConvertPhaseToPolyDurations(const VecDurations& phase_durations) const;
120 
129  virtual double
130  GetDerivativeOfPolyDurationWrtPhaseDuration(int polynomial_id) const;
131 
140  virtual int
141  GetNumberOfPrevPolynomialsInPhase(int polynomial_id) const;
142 
147  virtual bool IsInConstantPhase(int polynomial_id) const;
148 
149 private:
150  std::vector<PolyInfo> polynomial_info_;
151 
152  // maps from the nodes that are actually optimized over to all the nodes.
153  // Optimized nodes are sometimes used twice in a constant phase.
154  // This is where the constant phases are enforced.
155  std::map<OptNodeIs, NodeIds > optnode_to_node_;
156 
160  int GetPolyIDAtStartOfPhase(int phase) const;
161 
162  static std::map<OptNodeIs, NodeIds>
163  GetOptNodeToNodeMappings(const std::vector<PolyInfo>&);
164 
170  void SetBoundsEEMotion();
171 
177  void SetBoundsEEForce();
178 
179  std::vector<int> GetAdjacentPolyIds(int node_id) const;
180 
181 };
182 } /* namespace towr */
183 
184 #endif /* TOWR_VARIABLES_PHASE_NODES_H_ */
Nodes that are associated to either swing or stance phases.
Definition: phase_nodes.h:46
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
virtual ~PhaseNodes()=default
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
int n_polys_in_phase_
the number of polynomials used for this phase.
Definition: phase_nodes.h:60
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
int phase_
The phase ID this polynomial represents.
Definition: phase_nodes.h:58
std::vector< int > NodeIds
Definition: phase_nodes.h:50
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
std::shared_ptr< Nodes > Ptr
Definition: nodes.h:54
bool is_constant_
Does this polynomial represent a constant phase.
Definition: phase_nodes.h:61
std::vector< int > GetAdjacentPolyIds(int node_id) const
Definition: phase_nodes.cc:219
int GetPolyIDAtStartOfPhase(int phase) const
Definition: phase_nodes.cc:196
int GetPhase(int node_id) const
Definition: phase_nodes.cc:187
int GetNodeIDAtStartOfPhase(int phase) const
Definition: phase_nodes.cc:212
int poly_in_phase_
is this the 1st, 2nd, ... polynomial or this phase.
Definition: phase_nodes.h:59
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


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