vertex_interface.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_VERTEX_INTERFACE_H_
26 #define SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_HYPER_GRAPH_VERTEX_INTERFACE_H_
27 
28 #include <corbo-core/types.h>
29 
30 #include <memory>
31 #include <set>
32 
33 namespace corbo {
34 
35 class EdgeInterface; // Forward definition, include in child headers
36 class BaseEdge; // Forward definition, include in child headers
37 class BaseMixedEdge; // Forward definition, include in child headers
38 
54 {
55  friend class VertexSetInterface;
56 
57  public:
58  using Ptr = std::shared_ptr<VertexInterface>;
59  using UPtr = std::unique_ptr<VertexInterface>;
60 
62  virtual ~VertexInterface() {}
63 
65  virtual int getDimension() const = 0;
67  virtual int getDimensionUnfixed() const = 0;
69  virtual bool isFixed() const { return getDimensionUnfixed() == 0; }
70 
72  void registerObjectiveEdge(BaseEdge* edge);
76  void registerEqualityEdge(BaseEdge* edge);
78  void registerInequalityEdge(BaseEdge* edge);
80  void registerMixedEdge(BaseMixedEdge* edge);
83  {
84  _edges_objective.clear();
85  _edges_lsq_objective.clear();
86  _edges_equalities.clear();
87  _edges_inequalities.clear();
88  _edges_mixed.clear();
89  }
90 
92  virtual void plus(int idx, double inc) = 0;
94  virtual void plus(const double* inc) = 0;
96  virtual void plusUnfixed(const double* inc) = 0;
97 
99  virtual const double* getData() const = 0;
101  virtual double* getDataRaw() = 0;
106 
108  virtual void setData(int idx, double data) = 0;
109 
111  virtual bool hasFixedComponents() const = 0;
112 
114  virtual bool isFixedComponent(int idx) const = 0;
115 
117  virtual void setLowerBounds(const Eigen::Ref<const Eigen::VectorXd>& lb) = 0;
119  virtual void setUpperBounds(const Eigen::Ref<const Eigen::VectorXd>& ub) = 0;
121  virtual void setLowerBound(int idx, double lb) = 0;
123  virtual void setUpperBound(int idx, double ub) = 0;
125  virtual bool hasFiniteBounds() const = 0;
127  virtual bool hasFiniteLowerBounds() const = 0;
129  virtual bool hasFiniteUpperBounds() const = 0;
131  virtual bool hasFiniteLowerBound(int idx) const = 0;
133  virtual bool hasFiniteUpperBound(int idx) const = 0;
135  virtual int getNumberFiniteLowerBounds(bool unfixed_only) const = 0;
137  virtual int getNumberFiniteUpperBounds(bool unfixed_only) const = 0;
139  virtual int getNumberFiniteBounds(bool unfixed_only) const = 0;
140 
142  virtual const double* getLowerBounds() const = 0;
146  virtual const double* getUpperBounds() const = 0;
149 
151  const std::set<BaseEdge*>& getConnectedObjectiveEdgesRef() const { return _edges_objective; }
153  const std::set<BaseEdge*>& getConnectedLsqObjectiveEdgesRef() const { return _edges_lsq_objective; }
155  const std::set<BaseEdge*>& getConnectedEqualityEdgesRef() const { return _edges_equalities; }
157  const std::set<BaseEdge*>& getConnectedInequalityEdgesRef() const { return _edges_inequalities; }
159  const std::set<BaseMixedEdge*>& getConnectedMixedEdgesRef() const { return _edges_mixed; }
160 
161  // Backup values
162  virtual void push() = 0;
163  virtual void pop() = 0;
164  virtual void top() = 0;
165  virtual void discardTop() = 0;
166  virtual void clear() = 0;
167  virtual void clearBackups() { clear(); }
168  // virtual void copyBackup(int k, double* values) = 0; //!< Make sure that values complies with dimension()
169  virtual int getNumBackups() const = 0;
170 
172  int getVertexIdx() const { return _vertex_idx; }
174  // int getNumObjectiveEdgesWithCustomJacobian() const;
176  // int getNumEqualityEdgesWithCustomJacobian() const;
178  // int getNumInequalityEdgesWithCustomJacobian() const;
179 
180  private:
181  std::set<BaseEdge*> _edges_objective;
182  std::set<BaseEdge*> _edges_lsq_objective;
183  std::set<BaseEdge*> _edges_equalities;
184  std::set<BaseEdge*> _edges_inequalities;
185  std::set<BaseMixedEdge*> _edges_mixed;
186 
187  int _vertex_idx = 0;
188  // int _num_edges_with_custom_jacob = 0; //!< we can skip jacobian computation for this vertex if all edges provide their own jacobian
189 };
190 
191 } // namespace corbo
192 
193 #endif // SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_HYPER_GRAPH_VERTEX_INTERFACE_H_
void registerMixedEdge(BaseMixedEdge *edge)
Register an adjacent mixed edge.
void registerObjectiveEdge(BaseEdge *edge)
Register an adjacent objective edge.
virtual void clearBackups()
virtual void top()=0
Restore the previously stored values of the backup stack WITHOUT removing them from the stack...
virtual void setLowerBound(int idx, double lb)=0
Define lower bound on a single component of the vertex (0 <= idx < getDimension()) ...
virtual ~VertexInterface()
Virtual destructor.
Abstract class representing a set of vertices.
Definition: vertex_set.h:45
virtual bool hasFiniteBounds() const =0
Check if finite bounds (lower or upper) are provided.
std::set< BaseMixedEdge * > _edges_mixed
connected mixed edges
virtual bool hasFiniteLowerBound(int idx) const =0
Check if finite lower bound for a single component is provided.
virtual int getNumberFiniteLowerBounds(bool unfixed_only) const =0
Get number of finite lower bounds.
std::shared_ptr< VertexInterface > Ptr
void registerInequalityEdge(BaseEdge *edge)
Register an adjacent inequality constraint edge.
A matrix or vector expression mapping an existing array of data.
Definition: Map.h:94
virtual void pop()=0
Restore the previously stored values of the backup stack and remove them from the stack...
virtual bool isFixed() const
Check if all components are fixed.
virtual int getDimension() const =0
Return number of elements/values/components stored in this vertex.
Generic interface class for vertices.
int getVertexIdx() const
Retrieve current edge index (warning, this value is determined within the related VertexSetInterface ...
std::unique_ptr< VertexInterface > UPtr
const std::set< BaseMixedEdge * > & getConnectedMixedEdgesRef() const
Raw access for connected mixed edges.
virtual int getNumBackups() const =0
Return the current size/number of backups of the backup stack.
Eigen::Map< const Eigen::VectorXd > getDataMap() const
Get a read-only Eigen::Map to the values of the vertex.
virtual const double * getLowerBounds() const =0
Read-only raw access to lower bounds [getDimension() x 1].
const std::set< BaseEdge * > & getConnectedLsqObjectiveEdgesRef() const
Raw access for connected least-squares objective edges.
std::set< BaseEdge * > _edges_objective
Retrieve number of connected objective edges with custom Jacobian.
virtual void discardTop()=0
Delete the previously made backup from the stack without restoring it.
virtual void plusUnfixed(const double *inc)=0
Define the increment for the unfixed components of the vertex: x += inc with dim(inc)=getDimensionUnf...
Eigen::Map< const Eigen::VectorXd > getUpperBoundsMap() const
Read-only Eigen::Map for upper bounds [getDimension() x 1].
virtual int getDimensionUnfixed() const =0
Return number of unfixed elements (unfixed elements are skipped as parameters in the Hessian and Jaco...
virtual bool hasFiniteUpperBounds() const =0
Check if finite upper bounds are provided.
std::set< BaseEdge * > _edges_lsq_objective
connected least-squares objective edges
virtual void setUpperBounds(const Eigen::Ref< const Eigen::VectorXd > &ub)=0
Define upper bounds on the vertex values [getDimension() x 1].
virtual void setUpperBound(int idx, double ub)=0
Define upper bound on a single component of the vertex (0 <= idx < getDimension()) ...
virtual const double * getUpperBounds() const =0
Read-only raw access to upper bounds [getDimension() x 1].
Eigen::Map< Eigen::VectorXd > getDataRawMap()
Get a Eigen::Map to the values of the vertex.
virtual bool hasFiniteLowerBounds() const =0
Check if finite lower bounds are provided.
void clearConnectedEdges()
Clear all connected edges.
virtual bool hasFiniteUpperBound(int idx) const =0
Check if finite upper bound for a single component is provided.
int _vertex_idx
vertex index in jacobian or hessian (determined by friend class HyperGraph).
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
virtual void setLowerBounds(const Eigen::Ref< const Eigen::VectorXd > &lb)=0
Define lower bounds on the vertex values [getDimension() x 1].
virtual double * getDataRaw()=0
Get write access to the values of the vertex.
virtual void plus(int idx, double inc)=0
Add value to a specific component of the vertex: x[idx] += inc.
const std::set< BaseEdge * > & getConnectedObjectiveEdgesRef() const
Raw access for connected objective edges.
virtual const double * getData() const =0
Get read-only raw access to the values of the vertex.
std::set< BaseEdge * > _edges_inequalities
connected inequality constraint edges
virtual int getNumberFiniteUpperBounds(bool unfixed_only) const =0
Get number of finite upper bounds.
const std::set< BaseEdge * > & getConnectedEqualityEdgesRef() const
Raw access for connected equality constraint edges.
std::set< BaseEdge * > _edges_equalities
connected equality constraint edges
virtual bool hasFixedComponents() const =0
Check if the vertex has fixed components.
void registerEqualityEdge(BaseEdge *edge)
Register an adjacent equality constraint edge.
virtual void setData(int idx, double data)=0
Write data to to a specific component.
const std::set< BaseEdge * > & getConnectedInequalityEdgesRef() const
Raw access for connected inequality constraint edges.
Eigen::Map< const Eigen::VectorXd > getLowerBoundsMap() const
Read-only Eigen::Map for lower bounds [getDimension() x 1].
virtual void push()=0
Store all values into a internal backup stack.
virtual int getNumberFiniteBounds(bool unfixed_only) const =0
Get number of finite upper bounds (either upper or lower must be finite)
void registerLsqObjectiveEdge(BaseEdge *edge)
Register an adjacent least-squares objective edge.
virtual void clear()=0
Clear complete backup container.
virtual bool isFixedComponent(int idx) const =0
Check if individual components are fixed or unfixed.


control_box_rst
Author(s): Christoph Rösmann
autogenerated on Mon Feb 28 2022 22:07:58