nodes_variables.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 
72 public:
73  using Ptr = std::shared_ptr<NodesVariables>;
74  using VecDurations = std::vector<double>;
76 
85  struct NodeValueInfo {
86  int id_;
88  int dim_;
89 
90  NodeValueInfo() = default;
91  NodeValueInfo(int node_id, Dx deriv, int node_dim);
92  int operator==(const NodeValueInfo& right) const;
93  };
94 
105  virtual std::vector<NodeValueInfo> GetNodeValuesInfo(int opt_idx) const = 0;
106 
114  int GetOptIndex(const NodeValueInfo& nvi) const;
115  static const int NodeValueNotOptimized = -1;
116 
125  VectorXd GetValues () const override;
126 
137  void SetVariables (const VectorXd&x) override;
138 
142  VecBound GetBounds () const override;
143 
147  const std::vector<Node> GetNodes() const;
148 
152  int GetPolynomialCount() const;
153 
157  const std::vector<Node> GetBoundaryNodes(int poly_id) const;
158 
159  enum Side {Start=0, End};
165  static int GetNodeId(int poly_id, Side side);
166 
171  void AddObserver(ObserverPtr const spline);
172 
176  int GetDim() const;
177 
184  void SetByLinearInterpolation(const VectorXd& initial_val,
185  const VectorXd& final_val,
186  double t_total);
187 
194  void AddStartBound (Dx deriv, const std::vector<int>& dimensions,
195  const VectorXd& val);
196 
203  void AddFinalBound(Dx deriv, const std::vector<int>& dimensions,
204  const VectorXd& val);
205 
206 protected:
211  NodesVariables (const std::string& variable_name);
212  virtual ~NodesVariables () = default;
213 
215  std::vector<Node> nodes_;
216  int n_dim_;
217 
218 private:
222  void UpdateObservers() const;
223  std::vector<ObserverPtr> observers_;
224 
232  void AddBounds(int node_id, Dx deriv, const std::vector<int>& dim,
233  const VectorXd& values);
239  void AddBound(const NodeValueInfo& node_info, double value);
240 };
241 
242 } /* namespace towr */
243 
244 #endif /* TOWR_VARIABLES_NODE_VALUES_H_ */
Base class to receive up-to-date values of the NodeVariables.
const std::vector< Node > GetNodes() const
VectorXd GetValues() const override
Pure optimization variables that define the nodes.
int id_
ID of the associated node (0 =< id < number of nodes in spline).
void AddBound(const NodeValueInfo &node_info, double value)
Restricts a specific optimization variables.
NodesVariables(const std::string &variable_name)
void SetVariables(const VectorXd &x) override
Sets some node positions and velocity from the optimization variables.
int dim_
Dimension (x,y,z) of that derivative.
Position and velocity of nodes used to generate a Hermite spline.
virtual ~NodesVariables()=default
static const int NodeValueNotOptimized
std::vector< Node > nodes_
std::shared_ptr< Component > Ptr
static int GetNodeId(int poly_id, Side side)
The node ID that belongs to a specific side of a specific polynomial.
Semantic information associated with a scalar node value.
VecBound GetBounds() const override
int GetPolynomialCount() const
Dx deriv_
Derivative (pos,vel) of the node with that ID.
void UpdateObservers() const
Notifies the subscribed observers that the node values changes.
void AddStartBound(Dx deriv, const std::vector< int > &dimensions, const VectorXd &val)
Restricts the first node in the spline.
virtual std::vector< NodeValueInfo > GetNodeValuesInfo(int opt_idx) const =0
Node values affected by one specific optimization variable.
const std::vector< Node > GetBoundaryNodes(int poly_id) const
std::vector< double > VecDurations
void AddBounds(int node_id, Dx deriv, const std::vector< int > &dim, const VectorXd &values)
Bounds a specific node variables.
int GetOptIndex(const NodeValueInfo &nvi) const
Index in the optimization vector for a specific nodes&#39; pos/vel.
void AddFinalBound(Dx deriv, const std::vector< int > &dimensions, const VectorXd &val)
Restricts the last node in the spline.
void SetByLinearInterpolation(const VectorXd &initial_val, const VectorXd &final_val, double t_total)
Sets nodes pos/vel equally spaced from initial to final position.
VecBound bounds_
the bounds on the node values.
std::vector< Bounds > VecBound
void AddObserver(ObserverPtr const spline)
Adds a dependent observer that gets notified when the nodes change.
std::vector< ObserverPtr > observers_
Dx
< the values or derivative. For motions e.g. position, velocity, ...
Definition: state.h:41
Eigen::VectorXd VectorXd
int operator==(const NodeValueInfo &right) const


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