composite.h
Go to the documentation of this file.
1 /******************************************************************************
2 Copyright (c) 2017, 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 
36 #ifndef IFOPT_INCLUDE_OPT_COMPOSITE_H_
37 #define IFOPT_INCLUDE_OPT_COMPOSITE_H_
38 
39 #include <memory>
40 #include <string>
41 #include <vector>
42 
43 #include <Eigen/Dense>
44 #include <Eigen/Sparse>
45 
46 #include "bounds.h"
47 
48 namespace ifopt {
49 
71 class Component {
72 public:
73  using Ptr = std::shared_ptr<Component>;
74 
75  using Jacobian = Eigen::SparseMatrix<double, Eigen::RowMajor>;
76  using VectorXd = Eigen::VectorXd;
77  using VecBound = std::vector<Bounds>;
78 
89  Component(int num_rows, const std::string& name);
90  virtual ~Component() = default;
91 
99  virtual VectorXd GetValues() const = 0;
100 
108  virtual VecBound GetBounds() const = 0;
109 
116  virtual void SetVariables(const VectorXd& x) = 0;
117 
125  virtual Jacobian GetJacobian() const = 0;
126 
130  int GetRows() const;
131 
135  std::string GetName() const;
136 
140  virtual void Print() const;
141 
148  void SetRows(int num_rows);
149  static const int kSpecifyLater = -1;
150 
151 private:
153  std::string name_;
154 };
155 
156 
157 
168 class Composite : public Component {
169 public:
170  using Ptr = std::shared_ptr<Composite>;
171  using ComponentVec = std::vector<Component::Ptr>;
172 
181  Composite(const std::string& name, bool is_cost);
182  virtual ~Composite() = default;
183 
184  // see Component for documentation
185  VectorXd GetValues () const override;
186  Jacobian GetJacobian () const override;
187  VecBound GetBounds () const override;
188  void SetVariables(const VectorXd& x) override;
189  void Print() const override;
190 
196  const Component::Ptr GetComponent(std::string name) const;
197 
204  template<typename T> std::shared_ptr<T>
205  GetComponent(const std::string& name) const;
206 
210  void AddComponent (const Component::Ptr&);
211 
215  void ClearComponents();
216 
220  const ComponentVec GetComponents() const;
221 
222 private:
224  bool is_cost_;
225 };
226 
227 
228 // implementation of template functions
229 template<typename T>
230 std::shared_ptr<T> Composite::GetComponent(const std::string& name) const
231 {
232  Component::Ptr c = GetComponent(name);
233  return std::dynamic_pointer_cast<T>(c);
234 }
235 
236 
237 } /* namespace opt */
238 
239 #endif /* IFOPT_INCLUDE_OPT_COMPOSITE_H_ */
virtual VectorXd GetValues() const =0
Returns the "values" of whatever this component represents.
const Component::Ptr GetComponent(std::string name) const
Access generic component with the specified name.
Definition: composite.cc:87
std::string name_
Definition: composite.h:153
static const int kSpecifyLater
Definition: composite.h:149
Component(int num_rows, const std::string &name)
Creates a component.
Definition: composite.cc:36
std::vector< Component::Ptr > ComponentVec
Definition: composite.h:171
std::string GetName() const
Returns the name (id) of this component.
Definition: composite.cc:55
std::shared_ptr< Component > Ptr
Definition: composite.h:73
virtual void SetVariables(const VectorXd &x)=0
Sets the optimization variables from an Eigen vector.
void SetRows(int num_rows)
Sets the number of rows of this component.
Definition: composite.cc:49
ComponentVec components_
Definition: composite.h:223
Eigen::SparseMatrix< double, Eigen::RowMajor > Jacobian
Definition: composite.h:75
virtual Jacobian GetJacobian() const =0
Returns derivatives of each row w.r.t. the variables.
Definition: bounds.h:33
Interface representing either Variable, Cost or Constraint.
Definition: composite.h:71
virtual void Print() const
Prints the relevant information (name, rows, values) of this component.
Definition: composite.cc:181
A collection of components which is treated as another Component.
Definition: composite.h:168
std::vector< Bounds > VecBound
Definition: composite.h:77
int GetRows() const
Returns the number of rows of this component.
Definition: composite.cc:43
virtual ~Component()=default
virtual VecBound GetBounds() const =0
Returns the "bounds" of this component.
Eigen::VectorXd VectorXd
Definition: composite.h:76


ifopt_core
Author(s): Alexander W. Winkler
autogenerated on Thu Apr 19 2018 02:47:37