nodes.h
Go to the documentation of this file.
00001 /******************************************************************************
00002 Copyright (c) 2018, Alexander W. Winkler. All rights reserved.
00003 
00004 Redistribution and use in source and binary forms, with or without
00005 modification, are permitted provided that the following conditions are met:
00006 
00007 * Redistributions of source code must retain the above copyright notice, this
00008   list of conditions and the following disclaimer.
00009 
00010 * Redistributions in binary form must reproduce the above copyright notice,
00011   this list of conditions and the following disclaimer in the documentation
00012   and/or other materials provided with the distribution.
00013 
00014 * Neither the name of the copyright holder nor the names of its
00015   contributors may be used to endorse or promote products derived from
00016   this software without specific prior written permission.
00017 
00018 THIS SOFTWARE IS PROVIDED BY THE COPYRIGHT HOLDERS AND CONTRIBUTORS "AS IS"
00019 AND ANY EXPRESS OR IMPLIED WARRANTIES, INCLUDING, BUT NOT LIMITED TO, THE
00020 IMPLIED WARRANTIES OF MERCHANTABILITY AND FITNESS FOR A PARTICULAR PURPOSE ARE
00021 DISCLAIMED. IN NO EVENT SHALL THE COPYRIGHT HOLDER OR CONTRIBUTORS BE LIABLE
00022 FOR ANY DIRECT, INDIRECT, INCIDENTAL, SPECIAL, EXEMPLARY, OR CONSEQUENTIAL
00023 DAMAGES (INCLUDING, BUT NOT LIMITED TO, PROCUREMENT OF SUBSTITUTE GOODS OR
00024 SERVICES; LOSS OF USE, DATA, OR PROFITS; OR BUSINESS INTERRUPTION) HOWEVER
00025 CAUSED AND ON ANY THEORY OF LIABILITY, WHETHER IN CONTRACT, STRICT LIABILITY,
00026 OR TORT (INCLUDING NEGLIGENCE OR OTHERWISE) ARISING IN ANY WAY OUT OF THE USE
00027 OF THIS SOFTWARE, EVEN IF ADVISED OF THE POSSIBILITY OF SUCH DAMAGE.
00028 ******************************************************************************/
00029 
00030 #ifndef TOWR_VARIABLES_NODE_VALUES_H_
00031 #define TOWR_VARIABLES_NODE_VALUES_H_
00032 
00033 #include <ifopt/variable_set.h>
00034 
00035 #include "state.h"
00036 #include "nodes_observer.h"
00037 
00038 namespace towr {
00039 
00040 
00052 class Nodes : public ifopt::VariableSet {
00053 public:
00054   using Ptr          = std::shared_ptr<Nodes>;
00055   using VecDurations = std::vector<double>;
00056   using ObserverPtr  = NodesObserver*;
00057 
00061   struct IndexInfo {
00062     int node_id_;   
00063     Dx node_deriv_; 
00064     int node_dim_;  
00065 
00066     IndexInfo() = default;
00067     IndexInfo(int node_id, Dx deriv, int node_dim);
00068     int operator==(const IndexInfo& right) const;
00069   };
00070 
00080   virtual std::vector<IndexInfo> GetNodeInfoAtOptIndex(int idx) const = 0;
00081 
00087   int Index(const IndexInfo& node_info) const;
00088   int Index(int node_id, Dx deriv, int node_dim) const;
00089 
00096   void InitializeNodesTowardsGoal(const VectorXd& initial_pos,
00097                                   const VectorXd& final_pos,
00098                                   double t_total);
00102   VectorXd GetValues () const override;
00103 
00108   void SetVariables (const VectorXd&x) override;
00109 
00113   virtual VecBound GetBounds () const override;
00114 
00118   const std::vector<Node> GetNodes() const;
00119 
00123   int GetPolynomialCount() const;
00124 
00128   const std::vector<Node> GetBoundaryNodes(int poly_id) const;
00129 
00130   enum Side {Start=0, End};
00136   static int GetNodeId(int poly_id, Side side);
00137 
00142   void AddObserver(ObserverPtr const spline);
00143 
00147   int GetDim() const;
00148 
00155   void AddStartBound (Dx deriv, const std::vector<int>& dimensions,
00156                       const VectorXd& val);
00157 
00164   void AddFinalBound(Dx deriv, const std::vector<int>& dimensions,
00165                      const VectorXd& val);
00166 
00167 protected:
00168 
00173   Nodes (int n_dim, const std::string& variable_name);
00174   virtual ~Nodes () = default;
00175 
00176   VecBound bounds_; 
00177 
00186   void InitMembers(int n_nodes, int n_variables);
00187 
00188 private:
00189   std::vector<Node> nodes_;
00190   int n_dim_;
00191 
00195   void UpdateObservers() const;
00196   std::vector<ObserverPtr> observers_;
00197 
00205   void AddBounds(int node_id, Dx deriv, const std::vector<int>& dim,
00206                  const VectorXd& values);
00212   void AddBound(const IndexInfo& node_info, double value);
00213 };
00214 
00215 } /* namespace towr */
00216 
00217 #endif /* TOWR_VARIABLES_NODE_VALUES_H_ */


towr_core
Author(s): Alexander W. Winkler
autogenerated on Mon Apr 9 2018 03:12:44