hyper_graph_optimization_problem_base.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_HYPER_GRAPH_OPTIMIZATION_PROBLEM_BASE_H_
26 #define SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_HYPER_GRAPH_HYPER_GRAPH_OPTIMIZATION_PROBLEM_BASE_H_
27 
29 
31 
32 #include <corbo-core/factory.h>
33 
34 #include <functional>
35 #include <memory>
36 
37 #if MESSAGE_SUPPORT
38 #include <corbo-communication/messages/optimization/hyper_graph_optimization_problem.pb.h>
39 #endif
40 
41 namespace corbo {
42 
71 {
72  public:
73  using Ptr = std::shared_ptr<BaseHyperGraphOptimizationProblem>;
74 
77 
78  virtual Ptr getInstance() const { return std::make_shared<BaseHyperGraphOptimizationProblem>(); }
79 
82 
84  {
85  _graph.setEdgeSet(edges);
86  _graph.setVertexSet(vertices);
87  }
88 
89  const HyperGraph& getGraph() const { return _graph; }
90  HyperGraph& getGraph() { return _graph; }
91 
92  virtual void precomputeGraphQuantities();
93  virtual void precomputeVertexQuantities();
94  virtual void precomputeEdgeQuantities();
95 
98 
101  {
103  return _dim_non_lsq_obj;
104  }
106  {
108  return _dim_lsq_obj;
109  }
110  int getObjectiveDimension() override
111  {
113  return (int)(_dim_lsq_obj > 0 || _dim_non_lsq_obj > 0);
114  }
116  int getEqualityDimension() override
117  {
119  return _dim_eq;
120  }
122  int getInequalityDimension() override
123  {
125  return _dim_ineq;
126  }
127 
129 
132 
133  // implmements interface method
134  double computeValueNonLsqObjective() override;
135 
136  // implements interface method
138 
139  // implements interface method
140  double computeValueObjective() override;
141 
142  // implements interface method
144 
145  // implements interface method
147 
148  // implements interface method
149  void computeValues(double& non_lsq_obj_value, Eigen::Ref<Eigen::VectorXd> lsq_obj_values, Eigen::Ref<Eigen::VectorXd> eq_values,
150  Eigen::Ref<Eigen::VectorXd> ineq_values) override;
151 
153 
156 
157  // implements interface method
158  double getParameterValue(int idx) override { return _graph.getVertexSetRaw()->getParameterValue(idx); }
159  // implements interface method
160  void setParameterValue(int idx, double x) override { _graph.getVertexSetRaw()->setParameterValue(idx, x); }
161  // implements interface method
163  // implements interface method
165 
166  // implements interface method
168  // implements interface method
170  {
171  _graph.getVertexSetRaw()->setBounds(lb, ub);
172  }
173  // implements interface method
174  double getLowerBound(int idx) override { return _graph.getVertexSetRaw()->getLowerBound(idx); }
175  // implements interface method
176  double getUpperBound(int idx) override { return _graph.getVertexSetRaw()->getUpperBound(idx); }
177  // implements interface method
178  void setLowerBound(int idx, double lb) override { _graph.getVertexSetRaw()->setLowerBound(idx, lb); }
179  // implements interface method
180  void setUpperBound(int idx, double ub) override { _graph.getVertexSetRaw()->setUpperBound(idx, ub); }
181 
183 
186 
187  // implements interface method
188  int getParameterDimension() override
189  {
191  return _dim_param;
192  }
193 
194  // implements interface method
196  // implements interface method
197  void applyIncrement(int idx, double increment) override { _graph.getVertexSetRaw()->applyIncrementNonFixed(idx, increment); }
198 
199  // implements interface method
201  // implements interface method
202  void restoreBackupParameters(bool keep_backup) override { _graph.getVertexSetRaw()->restoreBackupParametersActiveVertices(keep_backup); }
203  // implements interface method
205 
207 
210 
211  // implements interface method
213 
215 
218 
219  // implements interface method
220  int finiteCombinedBoundsDimension() override;
221  // implements interface method
222  int finiteBoundsDimension() override;
223  // implements interface method
224  void computeValuesActiveInequality(Eigen::Ref<Eigen::VectorXd> values, double weight = 1.0) override;
225  // implements interface method
227  // implements interface method
229  // implements interface method
231  Eigen::Ref<Eigen::VectorXd> x_finite_bounds) override;
232 
233  void computeDenseJacobianFiniteCombinedBounds(Eigen::Ref<Eigen::MatrixXd> jacobian, double weight = 1.0) override;
236  void computeSparseJacobianFiniteCombinedBoundsValues(Eigen::Ref<Eigen::VectorXd> values, double weight = 1.0) override;
237 
239 
241 
243  bool checkIfAllUnfixedParam(std::function<bool(double, int)> fun);
244 
245  void clear() override;
246 
247 #ifdef MESSAGE_SUPPORT
248  // implements interface method
249  virtual void toMessage(corbo::messages::HyperGraphOptimizationProblem& message) const {}
250  // implements interface method
251  virtual void fromMessage(const corbo::messages::HyperGraphOptimizationProblem& message, std::stringstream* issues = nullptr) {}
252 #endif
253 
254  protected:
256  bool _graph_precomputed = false;
257 
258  int _dim_param = 0;
260  int _dim_lsq_obj = 0;
261  int _dim_eq = 0;
262  int _dim_ineq = 0;
263 };
264 
266 #define FACTORY_REGISTER_HYPER_GRAPH_OPTIMIZATION_PROBLEM(type) FACTORY_REGISTER_OBJECT_ID(type, BaseHyperGraphOptimizationProblem, 100)
267 
268 } // namespace corbo
269 
270 #endif // SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_HYPER_GRAPH_HYPER_GRAPH_OPTIMIZATION_PROBLEM_BASE_H_
bool hasOnlyLeastSquaresObjectives() const
Definition: edge_set.h:173
Generic factory object.
Definition: factory.h:68
Hyper-graph optimization problem formulation.
Scalar * x
void applyIncrement(int idx, double increment) override
Apply increment to the current parameter set (single element overload)
VertexSetInterface * getVertexSetRaw() const
Definition: hyper_graph.h:77
hyper-graph representation
Definition: hyper_graph.h:46
std::shared_ptr< BaseHyperGraphOptimizationProblem > Ptr
int getObjectiveDimension() override
Get dimension of the objective (should be zero or one, includes Lsq objectives if present) ...
void computeDenseJacobianFiniteCombinedBounds(Eigen::Ref< Eigen::MatrixXd > jacobian, double weight=1.0) override
Compute the Jacobian for finite combined bounds.
void setParameterValue(int idx, double x) override
Set specific value of the parameter vector.
void setParameterVector(const Eigen::Ref< const Eigen::VectorXd > &x)
Definition: vertex_set.cpp:133
void setUpperBound(int idx, double ub) override
Set specific upper bound of a parameter.
void applyIncrement(const Eigen::Ref< const Eigen::VectorXd > &increment) override
Apply increment to the current parameter set.
int getParameterDimension() override
Effictive dimension of the optimization parameter set (changeable, non-fixed part) ...
void restoreBackupParameters(bool keep_backup) override
Discard last backup (or all)
static Factory< BaseHyperGraphOptimizationProblem > & getFactory()
Get access to the accociated factory.
void applyIncrementNonFixed(const Eigen::Ref< const Eigen::VectorXd > &increment)
Active vertices related methods.
Definition: vertex_set.cpp:357
corbo::HyperGraphOptimizationProblemEdgeBased HyperGraphOptimizationProblem
void setLowerBound(int idx, double lb) override
Set specific lower bound of a parameter.
int finiteCombinedBoundsDimension() override
Dimension of the set of finite bounds (combined such that each ub and lb component define a single di...
void computeDistanceFiniteCombinedBounds(Eigen::Ref< Eigen::VectorXd > values) override
Compute the distance to finite bound values (combined lower and upper)
void computeValuesLsqObjective(Eigen::Ref< Eigen::VectorXd > values) override
Compute the objective function values f(x) for the current parameter set.
int getLsqObjectiveDimension() override
Total dimension of least-squares objective function terms.
void computeValuesEquality(Eigen::Ref< Eigen::VectorXd > values) override
Compute the equality constraint values ceq(x) for the current parameter set.
void setVertexSet(VertexSetInterface::Ptr vertices)
Definition: hyper_graph.h:68
double getLowerBound(int idx) override
Return specific lower bound value of a parameter.
void setParameterValue(int idx, double x)
Definition: vertex_set.cpp:71
void discardBackupParametersActiveVertices(bool all=false)
Definition: vertex_set.cpp:448
void computeValuesActiveInequality(Eigen::Ref< Eigen::VectorXd > values, double weight=1.0) override
Compute the values of the active inequality constraints (elementwise max(0, c(x))) ...
BaseHyperGraphOptimizationProblem(OptimizationEdgeSet::Ptr edges, VertexSetInterface::Ptr vertices)
Generic interface for optimization problem definitions.
void computeSparseJacobianFiniteCombinedBoundsValues(Eigen::Ref< Eigen::VectorXd > values, double weight=1.0) override
double getParameterValue(int idx)
Definition: vertex_set.cpp:38
std::shared_ptr< OptimizationEdgeSet > Ptr
Definition: edge_set.h:77
void restoreBackupParametersActiveVertices(bool keep_backup)
Definition: vertex_set.cpp:436
void getParametersAndBoundsFinite(Eigen::Ref< Eigen::VectorXd > lb_finite_bounds, Eigen::Ref< Eigen::VectorXd > ub_finite_bounds, Eigen::Ref< Eigen::VectorXd > x_finite_bounds) override
Return bound and parameter vectors only for finite boudns.
void computeDenseJacobianFiniteCombinedBoundsIdentity(Eigen::Ref< Eigen::MatrixXd > jacobian) override
Compute the Jacobian for finite combined bounds.
static Factory & instance()
< Retrieve static instance of the factory
Definition: factory.h:72
void getParameterVector(Eigen::Ref< Eigen::VectorXd > x)
Definition: vertex_set.cpp:107
void computeLowerAndUpperBoundDiff(Eigen::Ref< Eigen::VectorXd > lb_minus_x, Eigen::Ref< Eigen::VectorXd > ub_minus_x) override
Compute the distance between parameters and bounds.
A matrix or vector expression mapping an existing expression.
Definition: Ref.h:192
void computeValuesInequality(Eigen::Ref< Eigen::VectorXd > values) override
Compute the inequality constraint values c(x) for the current parameter set.
double getUpperBound(int idx)
Definition: vertex_set.cpp:252
void setGraph(OptimizationEdgeSet::Ptr edges, VertexSetInterface::Ptr vertices)
int finiteBoundsDimension() override
Dimension of the set of finite bounds (individual bounds ub and lb)
double getParameterValue(int idx) override
Return specific value of the parameter vector.
void setUpperBound(int idx, double ub)
Definition: vertex_set.cpp:321
void setBounds(const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub)
Definition: vertex_set.cpp:189
bool isLeastSquaresProblem() const override
Check if the underlying problem is defined in the least squares form.
void getBounds(Eigen::Ref< Eigen::VectorXd > lb, Eigen::Ref< Eigen::VectorXd > ub) override
Get lower and upper bound vector.
void backupParameters() override
Restore parameter set from the last backup and keep backup if desired.
void setLowerBound(int idx, double lb)
Definition: vertex_set.cpp:285
int getNonLsqObjectiveDimension() override
Total dimension of objective function terms.
double getLowerBound(int idx)
Definition: vertex_set.cpp:219
std::shared_ptr< VertexSetInterface > Ptr
Definition: vertex_set.h:48
bool checkIfAllUnfixedParam(std::function< bool(double, int)> fun)
Check if a function taking the parameter value and unfixed-idx is true for all unfixed parameter valu...
int getEqualityDimension() override
Total dimension of equality constraints.
void computeValues(double &non_lsq_obj_value, Eigen::Ref< Eigen::VectorXd > lsq_obj_values, Eigen::Ref< Eigen::VectorXd > eq_values, Eigen::Ref< Eigen::VectorXd > ineq_values) override
void setParameterVector(const Eigen::Ref< const Eigen::VectorXd > &x) override
Set complete parameter vector.
OptimizationEdgeSet * getEdgeSetRaw() const
Definition: hyper_graph.h:76
void setEdgeSet(OptimizationEdgeSet::Ptr edges)
Definition: hyper_graph.h:67
void getParameterVector(Eigen::Ref< Eigen::VectorXd > x) override
Return deep copy of the complete parameter vector.
int getInequalityDimension() override
Total dimension of general inequality constraints.
void setBounds(const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub) override
Set lower and upper bound vector.
void computeSparseJacobianFiniteCombinedBoundsStructure(Eigen::Ref< Eigen::VectorXi > i_row, Eigen::Ref< Eigen::VectorXi > j_col) override
void getBounds(Eigen::Ref< Eigen::VectorXd > lb, Eigen::Ref< Eigen::VectorXd > ub)
Definition: vertex_set.cpp:159
double getUpperBound(int idx) override
Return specific upper bound of a parameter.


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