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_NODE_VALUES_H_
31 #define TOWR_VARIABLES_NODE_VALUES_H_
32 
33 #include <ifopt/variable_set.h>
34 
35 #include "state.h"
36 #include "nodes_observer.h"
37 
38 namespace towr {
39 
40 
52 class Nodes : public ifopt::VariableSet {
53 public:
54  using Ptr = std::shared_ptr<Nodes>;
55  using VecDurations = std::vector<double>;
57 
61  struct IndexInfo {
62  int node_id_;
64  int node_dim_;
65 
66  IndexInfo() = default;
67  IndexInfo(int node_id, Dx deriv, int node_dim);
68  int operator==(const IndexInfo& right) const;
69  };
70 
80  virtual std::vector<IndexInfo> GetNodeInfoAtOptIndex(int idx) const = 0;
81 
87  int Index(const IndexInfo& node_info) const;
88  int Index(int node_id, Dx deriv, int node_dim) const;
89 
96  void InitializeNodesTowardsGoal(const VectorXd& initial_pos,
97  const VectorXd& final_pos,
98  double t_total);
102  VectorXd GetValues () const override;
103 
108  void SetVariables (const VectorXd&x) override;
109 
113  virtual VecBound GetBounds () const override;
114 
118  const std::vector<Node> GetNodes() const;
119 
123  int GetPolynomialCount() const;
124 
128  const std::vector<Node> GetBoundaryNodes(int poly_id) const;
129 
130  enum Side {Start=0, End};
136  static int GetNodeId(int poly_id, Side side);
137 
142  void AddObserver(ObserverPtr const spline);
143 
147  int GetDim() const;
148 
155  void AddStartBound (Dx deriv, const std::vector<int>& dimensions,
156  const VectorXd& val);
157 
164  void AddFinalBound(Dx deriv, const std::vector<int>& dimensions,
165  const VectorXd& val);
166 
167 protected:
168 
173  Nodes (int n_dim, const std::string& variable_name);
174  virtual ~Nodes () = default;
175 
176  VecBound bounds_;
177 
186  void InitMembers(int n_nodes, int n_variables);
187 
188 private:
189  std::vector<Node> nodes_;
190  int n_dim_;
191 
195  void UpdateObservers() const;
196  std::vector<ObserverPtr> observers_;
197 
205  void AddBounds(int node_id, Dx deriv, const std::vector<int>& dim,
206  const VectorXd& values);
212  void AddBound(const IndexInfo& node_info, double value);
213 };
214 
215 } /* namespace towr */
216 
217 #endif /* TOWR_VARIABLES_NODE_VALUES_H_ */
void AddBound(const IndexInfo &node_info, double value)
Restricts a specific optimization variables.
Definition: nodes.cc:195
Base class to receive up-to-date values of the NodeVariables.
virtual ~Nodes()=default
std::vector< Node > nodes_
Definition: nodes.h:189
VectorXd GetValues() const override
Definition: nodes.cc:112
std::vector< double > VecDurations
Definition: nodes.h:55
Eigen::VectorXd VectorXd
void UpdateObservers() const
Notifies the subscribed observers that the node values changes.
Definition: nodes.cc:134
void AddObserver(ObserverPtr const spline)
Adds a dependent observer that gets notified when the nodes change.
Definition: nodes.cc:141
virtual std::vector< IndexInfo > GetNodeInfoAtOptIndex(int idx) const =0
The node information that the optimization index represents.
Definition: nodes.cc:93
void InitializeNodesTowardsGoal(const VectorXd &initial_pos, const VectorXd &final_pos, double t_total)
Sets nodes pos/vel equally spaced from initial to final position.
Definition: nodes.cc:51
int node_dim_
the dimension (x,y,z) of that optimization index.
Definition: nodes.h:64
void AddFinalBound(Dx deriv, const std::vector< int > &dimensions, const VectorXd &val)
Restricts the last node in the spline.
Definition: nodes.cc:212
int n_dim_
Definition: nodes.h:190
Position and velocity of nodes used to generate a Hermite spline.
Definition: nodes.h:52
int Index(const IndexInfo &node_info) const
The index at which a specific node variable is stored.
Definition: nodes.cc:80
void AddBounds(int node_id, Dx deriv, const std::vector< int > &dim, const VectorXd &values)
Bounds a specific node variables.
Definition: nodes.cc:186
int GetDim() const
Definition: nodes.cc:162
std::shared_ptr< Nodes > Ptr
Definition: nodes.h:54
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
Nodes(int n_dim, const std::string &variable_name)
Definition: nodes.cc:36
int GetPolynomialCount() const
Definition: nodes.cc:168
std::vector< ObserverPtr > observers_
Definition: nodes.h:196
Dx node_deriv_
The derivative (pos,vel) of that optimziation index.
Definition: nodes.h:63
virtual VecBound GetBounds() const override
Definition: nodes.cc:174
Holds information about the node the optimization index represents.
Definition: nodes.h:61
int node_id_
The ID of the node of the optimization index.
Definition: nodes.h:62
void SetVariables(const VectorXd &x) override
Sets the node position and velocity optimization variables.
Definition: nodes.cc:124
int operator==(const IndexInfo &right) const
Definition: nodes.cc:220
const std::vector< Node > GetBoundaryNodes(int poly_id) const
Definition: nodes.cc:153
void AddStartBound(Dx deriv, const std::vector< int > &dimensions, const VectorXd &val)
Restricts the first node in the spline.
Definition: nodes.cc:204
Dx
< the values or derivative. For motions e.g. position, velocity, ...
Definition: state.h:41
const std::vector< Node > GetNodes() const
Definition: nodes.cc:180


towr_core
Author(s): Alexander W. Winkler
autogenerated on Sun Apr 8 2018 02:18:53