nodes_variables_phase_based.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_variables.h"
34 
35 namespace towr {
36 
60 public:
61  using Ptr = std::shared_ptr<NodesVariablesPhaseBased>;
62  using NodeIds = std::vector<int>;
63  using OptIndexMap = std::map<int, std::vector<NodeValueInfo> >;
64 
68  struct PolyInfo {
69  int phase_;
72  bool is_constant_;
73  PolyInfo(int phase, int poly_in_phase, int n_polys_in_phase, bool is_const);
74  };
75 
84  NodesVariablesPhaseBased (int phase_count,
85  bool first_phase_constant,
86  const std::string& var_name,
87  int n_polys_in_changing_phase);
88 
89  virtual ~NodesVariablesPhaseBased() = default;
90 
94  Eigen::Vector3d GetValueAtStartOfPhase(int phase) const;
95 
99  int GetNodeIDAtStartOfPhase(int phase) const;
100 
106  int GetPhase(int node_id) const;
107 
112  virtual bool IsConstantNode(int node_id) const;
113 
121 
128  virtual VecDurations
129  ConvertPhaseToPolyDurations(const VecDurations& phase_durations) const;
130 
139  virtual double
140  GetDerivativeOfPolyDurationWrtPhaseDuration(int polynomial_id) const;
141 
150  virtual int
151  GetNumberOfPrevPolynomialsInPhase(int polynomial_id) const;
152 
157  virtual bool IsInConstantPhase(int polynomial_id) const;
158 
159 protected:
168  std::vector<NodeValueInfo> GetNodeValuesInfo(int idx) const override {
169  return index_to_node_value_info_.at(idx);
170  }
171 
172  void SetNumberOfVariables(int n_variables);
173 
174 private:
176  std::vector<PolyInfo> polynomial_info_;
177 
179  int GetPolyIDAtStartOfPhase(int phase) const;
180 
182  std::vector<int> GetAdjacentPolyIds(int node_id) const;
183 };
184 
185 
192 public:
193  NodesVariablesEEMotion(int phase_count,
194  bool is_in_contact_at_start,
195  const std::string& name,
196  int n_polys_in_changing_phase);
197  virtual ~NodesVariablesEEMotion() = default;
198  OptIndexMap GetPhaseBasedEEParameterization ();
199 };
200 
201 
208 public:
209  NodesVariablesEEForce(int phase_count,
210  bool is_in_contact_at_start,
211  const std::string& name,
212  int n_polys_in_changing_phase);
213  virtual ~NodesVariablesEEForce() = default;
214  OptIndexMap GetPhaseBasedEEParameterization ();
215 };
216 
217 } /* namespace towr */
218 
219 #endif /* TOWR_VARIABLES_PHASE_NODES_H_ */
virtual VecDurations ConvertPhaseToPolyDurations(const VecDurations &phase_durations) const
Converts durations of swing and stance phases to polynomial durations.
int n_polys_in_phase_
the number of polynomials used for this phase.
std::map< int, std::vector< NodeValueInfo > > OptIndexMap
bool is_constant_
Does this polynomial represent a constant phase.
virtual bool IsConstantNode(int node_id) const
node is constant if either left or right polynomial belongs to a constant phase.
Holds semantic information each polynomial in spline.
int phase_
The phase ID this polynomial represents.
virtual ~NodesVariablesPhaseBased()=default
PolyInfo(int phase, int poly_in_phase, int n_polys_in_phase, bool is_const)
Position and velocity of nodes used to generate a Hermite spline.
std::shared_ptr< Component > Ptr
std::vector< PolyInfo > polynomial_info_
semantic information associated with each polynomial
OptIndexMap index_to_node_value_info_
Assign optimization variables to the correct node values.
virtual int GetNumberOfPrevPolynomialsInPhase(int polynomial_id) const
How many polynomials in the current phase come before.
Variables fully defining the endeffector forces.
std::vector< int > GetAdjacentPolyIds(int node_id) const
IDs of the polynomial to the left and right of node_id.
Variables fully defining the endeffector motion.
Eigen::Vector3d GetValueAtStartOfPhase(int phase) const
int poly_in_phase_
is this the 1st, 2nd, ... polynomial or this phase.
virtual double GetDerivativeOfPolyDurationWrtPhaseDuration(int polynomial_id) const
How a change in the phase duration affects the polynomial duration.
int GetPolyIDAtStartOfPhase(int phase) const
ID of the first polynomial of a phase.
std::vector< double > VecDurations
NodesVariablesPhaseBased(int phase_count, bool first_phase_constant, const std::string &var_name, int n_polys_in_changing_phase)
Constructs a variable set of node variables.
Nodes that are associated to either swing or stance phases.
std::vector< NodeValueInfo > GetNodeValuesInfo(int idx) const override
Node values affected by one specific optimization variable.
NodeIds GetIndicesOfNonConstantNodes() const
The indices of those nodes that don&#39;t belong to a constant phase.
virtual bool IsInConstantPhase(int polynomial_id) const
Is the polynomial constant, so not changing the value.


towr
Author(s): Alexander W. Winkler
autogenerated on Fri Apr 2 2021 02:14:16