edge.h
Go to the documentation of this file.
1 /*********************************************************************
2  *
3  * Software License Agreement
4  *
5  * Copyright (c) 2020,
6  * TU Dortmund - Institute of Control Theory and Systems Engineering.
7  * All rights reserved.
8  *
9  * This program is free software: you can redistribute it and/or modify
10  * it under the terms of the GNU General Public License as published by
11  * the Free Software Foundation, either version 3 of the License, or
12  * (at your option) any later version.
13  *
14  * This program is distributed in the hope that it will be useful,
15  * but WITHOUT ANY WARRANTY; without even the implied warranty of
16  * MERCHANTABILITY or FITNESS FOR A PARTICULAR PURPOSE. See the
17  * GNU General Public License for more details.
18  *
19  * You should have received a copy of the GNU General Public License
20  * along with this program. If not, see <https://www.gnu.org/licenses/>.
21  *
22  * Authors: Christoph Rösmann
23  *********************************************************************/
24 
25 #ifndef SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_HYPER_GRAPH_EDGE_H_
26 #define SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_HYPER_GRAPH_EDGE_H_
27 
28 #include <corbo-core/types.h>
31 
32 #include <corbo-core/utilities.h>
33 
34 #include <array>
35 #include <memory>
36 
37 namespace corbo {
38 
64 // template <class... Vertices>
65 // class Edge : public BaseEdge
66 //{
67 // public:
68 // using Ptr = std::shared_ptr<Edge>;
69 // using UPtr = std::unique_ptr<Edge>;
70 
71 // //! Return number of vertices at compile-time
72 // static constexpr const int numVerticesCompileTime = sizeof...(Vertices);
73 // //! Return edge dimension at compile-time
74 // static constexpr const int dimensionCompileTime = D;
75 
76 // //! Typedef to represent the vertex container.
77 // using VertexContainer = std::array<VertexInterface*, numVerticesCompileTime>;
78 
79 // // delete default constructor
80 // Edge() = delete;
81 
82 // /**
83 // * @brief Construct edge by providing connected vertices
84 // *
85 // * The order must match the order of template arguments provided to the class.
86 // * @warning Vertices must remain valid as long as the Edge is in use!
87 // */
88 // template <class... VerticesT>
89 // explicit Edge(VerticesT&... args) : BaseEdge(), _vertices({&args...})
90 // {
91 // // Check if types and number of template parameters match class template paremters for vertices
92 // static_assert(util::variadic_temp_equal<std::tuple<Vertices...>, std::tuple<VerticesT...>>::value,
93 // "BaseEdge(): Number and types of vertices passed via the constructor does not match number of class template parameters");
94 // } //!< Construct edge by passing all vertices references.
95 
96 // // implements interface method
97 // int getDimension() const override { return D; }
98 // // implements interface method
99 // int getNumVertices() const override { return numVerticesCompileTime; }
100 
101 // // implements interface method
102 // int verticesDimension() const override
103 // {
104 // int n = 0;
105 // for (VertexInterface* vertex : _vertices) n += vertex->getDimension();
106 // return n;
107 // }
108 
109 // // implements interface method
110 // bool isLinear() const override = 0;
111 // // implements interface method
112 // bool providesJacobian() const override { return false; }
113 
114 // // implements interface method
115 // void computeValues(double* values) override = 0;
116 
117 // // implements interface method
118 // VertexInterface* getVertexRaw(int idx) override
119 // {
120 // assert(idx < getNumVertices());
121 // return _vertices[idx];
122 // }
123 
124 // protected:
125 // const VertexContainer _vertices; //!< Vertex container
126 
127 // public:
128 // EIGEN_MAKE_ALIGNED_OPERATOR_NEW
129 //};
130 
147 template <class... Vertices>
148 class Edge : public BaseEdge
149 {
150  public:
151  using Ptr = std::shared_ptr<Edge>;
152  using ConstPtr = std::shared_ptr<const Edge>;
153  using UPtr = std::unique_ptr<Edge>;
154 
156  static constexpr const int numVerticesCompileTime = sizeof...(Vertices);
157 
159  using VertexContainer = std::array<VertexInterface*, numVerticesCompileTime>;
160 
161  // delete default constructor
162  Edge() = delete;
163 
170  template <class... VerticesT>
171  explicit Edge(VerticesT&... args) : BaseEdge(), _vertices({&args...})
172  {
173  // Check if types and number of template parameters match class template paremters for vertices
174  static_assert(util::variadic_temp_equal<std::tuple<Vertices...>, std::tuple<VerticesT...>>::value,
175  "Edge(): Number and types of vertices passed via the constructor does not match number of class template parameters");
176  }
177 
178  // implements interface method
179  int getDimension() const override = 0;
180  // implements interface method
181  int getNumVertices() const override { return numVerticesCompileTime; }
182 
183  // implements interface method
184  int verticesDimension() const override
185  {
186  int n = 0;
187  for (VertexInterface* vertex : _vertices) n += vertex->getDimension();
188  return n;
189  }
190 
191  // implements interface method
192  bool isLinear() const override = 0;
193  // implements interface method
194  bool providesJacobian() const override { return false; }
195 
196  // implements interface method
197  void computeValues(Eigen::Ref<Eigen::VectorXd> values) override = 0;
198 
199  // implements interface method
200  VertexInterface* getVertexRaw(int idx) override
201  {
202  assert(idx < getNumVertices());
203  return _vertices[idx];
204  }
205 
206  // implements interface method
207  const VertexInterface* getVertex(int idx) const override
208  {
209  assert(idx < getNumVertices());
210  return _vertices[idx];
211  }
212 
213  protected:
214  const VertexContainer _vertices;
215 
216  public:
218 };
219 
220 template <>
221 class Edge<> : public BaseEdge
222 {
223  public:
224  using Ptr = std::shared_ptr<Edge>;
225  using ConstPtr = std::shared_ptr<const Edge>;
226  using UPtr = std::unique_ptr<Edge>;
227 
229  using VertexContainer = std::vector<VertexInterface*>;
230 
231  // delete default constructor
232  Edge() = delete;
233 
234  explicit Edge(int num_vertices) { resizeVertexContainer(num_vertices); }
235 
237  void resizeVertexContainer(int n) { _vertices.resize(n); }
238 
239  void setVertex(int idx, VertexInterface& vertex)
240  {
241  assert(idx < (int)_vertices.size());
242  _vertices[idx] = &vertex;
243  }
244 
245  // implements interface method
246  int getDimension() const override = 0;
247  // implements interface method
248  int getNumVertices() const override { return _vertices.size(); }
249 
250  // implements interface method
251  int verticesDimension() const override
252  {
253  int n = 0;
254  for (VertexInterface* vertex : _vertices) n += vertex->getDimension();
255  return n;
256  }
257 
258  // implements interface method
259  bool isLinear() const override = 0;
260  // implements interface method
261  bool providesJacobian() const override { return false; }
262 
263  // implements interface method
264  void computeValues(Eigen::Ref<Eigen::VectorXd> values) override = 0;
265 
266  // implements interface method
267  VertexInterface* getVertexRaw(int idx) override
268  {
269  assert(idx < getNumVertices());
270  return _vertices[idx];
271  }
272 
273  // implements interface method
274  const VertexInterface* getVertex(int idx) const override
275  {
276  assert(idx < getNumVertices());
277  return _vertices[idx];
278  }
279 
280  protected:
282 
283  public:
285 };
286 
287 template <class... Vertices>
288 class MixedEdge : public BaseMixedEdge
289 {
290  public:
291  using Ptr = std::shared_ptr<MixedEdge>;
292  using ConstPtr = std::shared_ptr<const MixedEdge>;
293  using UPtr = std::unique_ptr<MixedEdge>;
294 
296  static constexpr const int numVerticesCompileTime = sizeof...(Vertices);
297 
299  using VertexContainer = std::array<VertexInterface*, numVerticesCompileTime>;
300 
301  // delete default constructor
302  MixedEdge() = delete;
303 
310  template <class... VerticesT>
311  explicit MixedEdge(VerticesT&... args) : BaseMixedEdge(), _vertices({&args...})
312  {
313  // Check if types and number of template parameters match class template paremters for vertices
314  static_assert(util::variadic_temp_equal<std::tuple<Vertices...>, std::tuple<VerticesT...>>::value,
315  "MixedEdge(): Number and types of vertices passed via the constructor does not match number of class template parameters");
316  }
317 
318  // implements interface method
319  int getObjectiveDimension() const override = 0;
320  // implements interface method
321  int getEqualityDimension() const override = 0;
322  // implements interface method
323  int getInequalityDimension() const override = 0;
324  // implements interface method
325  int getNumVertices() const override { return numVerticesCompileTime; }
326 
327  // implements interface method
328  int verticesDimension() const override
329  {
330  int n = 0;
331  for (VertexInterface* vertex : _vertices) n += vertex->getDimension();
332  return n;
333  }
334 
335  // implements interface method
336  // bool isLinear() const override = 0;
337  // implements interface method
338  // bool providesJacobian() const override { return false; }
339 
340  // implements interface method
341  void precompute() override = 0;
342  void computeObjectiveValues(Eigen::Ref<Eigen::VectorXd> obj_values) override = 0;
343  void computeEqualityValues(Eigen::Ref<Eigen::VectorXd> eq_values) override = 0;
344  void computeInequalityValues(Eigen::Ref<Eigen::VectorXd> ineq_values) override = 0;
345 
346  // implements interface method
347  VertexInterface* getVertexRaw(int idx) override
348  {
349  assert(idx < getNumVertices());
350  return _vertices[idx];
351  }
352 
353  // implements interface method
354  const VertexInterface* getVertex(int idx) const override
355  {
356  assert(idx < getNumVertices());
357  return _vertices[idx];
358  }
359 
360  protected:
361  const VertexContainer _vertices;
362 
363  public:
365 };
366 
367 template <>
368 class MixedEdge<> : public BaseMixedEdge
369 {
370  public:
371  using Ptr = std::shared_ptr<MixedEdge>;
372  using ConstPtr = std::shared_ptr<const MixedEdge>;
373  using UPtr = std::unique_ptr<MixedEdge>;
374 
376  using VertexContainer = std::vector<VertexInterface*>;
377 
378  // delete default constructor
379  MixedEdge() : BaseMixedEdge() {}
380 
381  explicit MixedEdge(int num_vertices) : BaseMixedEdge() { resizeVertexContainer(num_vertices); }
382 
384  void resizeVertexContainer(int n) { _vertices.resize(n); }
385 
386  void setVertex(int idx, VertexInterface& vertex)
387  {
388  assert(idx < (int)_vertices.size());
389  _vertices[idx] = &vertex;
390  }
391 
392  // implements interface method
393  int getObjectiveDimension() const override = 0;
394  // implements interface method
395  int getEqualityDimension() const override = 0;
396  // implements interface method
397  int getInequalityDimension() const override = 0;
398  // implements interface method
399  int getNumVertices() const override { return (int)_vertices.size(); }
400 
401  // implements interface method
402  int verticesDimension() const override
403  {
404  int n = 0;
405  for (VertexInterface* vertex : _vertices) n += vertex->getDimension();
406  return n;
407  }
408 
409  // implements interface method
410  // bool isLinear() const override = 0;
411  // implements interface method
412  // bool providesJacobian() const override { return false; }
413 
414  // implements interface method
415  void precompute() override = 0;
416  void computeObjectiveValues(Eigen::Ref<Eigen::VectorXd> obj_values) override = 0;
417  void computeEqualityValues(Eigen::Ref<Eigen::VectorXd> eq_values) override = 0;
418  void computeInequalityValues(Eigen::Ref<Eigen::VectorXd> ineq_values) override = 0;
419 
420  // implements interface method
421  VertexInterface* getVertexRaw(int idx) override
422  {
423  assert(idx < getNumVertices());
424  return _vertices[idx];
425  }
426 
427  // implements interface method
428  const VertexInterface* getVertex(int idx) const override
429  {
430  assert(idx < getNumVertices());
431  return _vertices[idx];
432  }
433 
434  protected:
436 
437  public:
439 };
440 
441 } // namespace corbo
442 
443 #endif // SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_HYPER_GRAPH_EDGE_H_
corbo::EdgeInterface::Ptr
std::shared_ptr< EdgeInterface > Ptr
Definition: edge_interface.h:81
corbo::Edge::VertexContainer
std::array< VertexInterface *, numVerticesCompileTime > VertexContainer
Typedef to represent the vertex container.
Definition: edge.h:203
corbo::BaseEdge
Definition: edge_interface.h:129
corbo::Edge<>::ConstPtr
std::shared_ptr< const Edge > ConstPtr
Definition: edge.h:247
corbo
Definition: communication/include/corbo-communication/utilities.h:37
corbo::MixedEdge::VertexContainer
std::array< VertexInterface *, numVerticesCompileTime > VertexContainer
Typedef to represent the vertex container.
Definition: edge.h:321
corbo::Edge::Edge
Edge()=delete
corbo::Edge::isLinear
bool isLinear() const override=0
Return true if the edge is linear (and hence its Hessian is always zero)
vector_vertex.h
corbo::MixedEdge::numVerticesCompileTime
static constexpr const int numVerticesCompileTime
Return number of vertices at compile-time.
Definition: edge.h:318
corbo::MixedEdge::_vertices
const VertexContainer _vertices
Vertex container.
Definition: edge.h:383
utilities.h
corbo::VertexInterface
Generic interface class for vertices.
Definition: vertex_interface.h:75
corbo::MixedEdge< VectorVertex, VectorVertex, ScalarVertex, VectorVertex, VectorVertex >::ConstPtr
std::shared_ptr< const MixedEdge > ConstPtr
Definition: edge.h:314
corbo::MixedEdge::getVertex
const VertexInterface * getVertex(int idx) const override
Definition: edge.h:376
corbo::Edge::providesJacobian
bool providesJacobian() const override
Return true if a custom Jacobian is provided (e.g. computeJacobian() is overwritten)
Definition: edge.h:238
corbo::BaseMixedEdge
Definition: edge_interface.h:239
corbo::MixedEdge
Definition: edge.h:310
corbo::MixedEdge::getNumVertices
int getNumVertices() const override
Return number of attached vertices.
Definition: edge.h:347
corbo::MixedEdge::getObjectiveDimension
int getObjectiveDimension() const override=0
edge_interface.h
corbo::MixedEdge::computeObjectiveValues
void computeObjectiveValues(Eigen::Ref< Eigen::VectorXd > obj_values) override=0
corbo::Edge::getVertex
const VertexInterface * getVertex(int idx) const override
Definition: edge.h:251
corbo::Edge::getNumVertices
int getNumVertices() const override
Return number of attached vertices.
Definition: edge.h:225
EIGEN_MAKE_ALIGNED_OPERATOR_NEW
#define EIGEN_MAKE_ALIGNED_OPERATOR_NEW
Definition: Memory.h:690
corbo::Edge<>::VertexContainer
std::vector< VertexInterface * > VertexContainer
Typedef to represent the vertex container.
Definition: edge.h:251
corbo::MixedEdge::computeInequalityValues
void computeInequalityValues(Eigen::Ref< Eigen::VectorXd > ineq_values) override=0
corbo::MixedEdge::MixedEdge
MixedEdge()=delete
corbo::Edge<>::Ptr
std::shared_ptr< Edge > Ptr
Definition: edge.h:246
corbo::EdgeInterface::UPtr
std::unique_ptr< EdgeInterface > UPtr
Definition: edge_interface.h:82
corbo::MixedEdge::getInequalityDimension
int getInequalityDimension() const override=0
Eigen::Ref
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
corbo::Edge::UPtr
std::unique_ptr< Edge > UPtr
Definition: edge.h:197
corbo::Edge::getVertexRaw
VertexInterface * getVertexRaw(int idx) override
Get access to vertex with index idx (0 <= idx < numVertices)
Definition: edge.h:244
corbo::Edge::getDimension
int getDimension() const override=0
Get dimension of the edge (dimension of the cost-function/constraint value vector)
corbo::MixedEdge::precompute
void precompute() override=0
corbo::Edge::computeValues
void computeValues(Eigen::Ref< Eigen::VectorXd > values) override=0
Compute function values.
corbo::MixedEdge::getEqualityDimension
int getEqualityDimension() const override=0
corbo::Edge::verticesDimension
int verticesDimension() const override
Return the combined dimension of all attached vertices (excluding fixed vertex components)
Definition: edge.h:228
corbo::Edge::Ptr
std::shared_ptr< Edge > Ptr
Definition: edge.h:195
corbo::MixedEdge::computeEqualityValues
void computeEqualityValues(Eigen::Ref< Eigen::VectorXd > eq_values) override=0
types.h
corbo::MixedEdge::getVertexRaw
VertexInterface * getVertexRaw(int idx) override
Get access to vertex with index idx (0 <= idx < numVertices)
Definition: edge.h:369
n
PlainMatrixType mat * n
Definition: eigenvalues.cpp:41
corbo::MixedEdge::verticesDimension
int verticesDimension() const override
Return the combined dimension of all attached vertices (excluding fixed vertex components)
Definition: edge.h:350
corbo::Edge::numVerticesCompileTime
static constexpr const int numVerticesCompileTime
Return number of vertices at compile-time.
Definition: edge.h:200
corbo::Edge<>::UPtr
std::unique_ptr< Edge > UPtr
Definition: edge.h:248
corbo::Edge::ConstPtr
std::shared_ptr< const Edge > ConstPtr
Definition: edge.h:196
corbo::Edge::_vertices
const VertexContainer _vertices
Vertex container.
Definition: edge.h:258


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:05:45