Go to the documentation of this file.
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_
38 #include <corbo-communication/messages/optimization/hyper_graph_optimization_problem.pb.h>
70 class BaseHyperGraphOptimizationProblem :
public OptimizationProblemInterface
73 using Ptr = std::shared_ptr<BaseHyperGraphOptimizationProblem>;
78 virtual Ptr getInstance()
const {
return std::make_shared<BaseHyperGraphOptimizationProblem>(); }
245 void clear()
override;
247 #ifdef MESSAGE_SUPPORT
266 #define FACTORY_REGISTER_HYPER_GRAPH_OPTIMIZATION_PROBLEM(type) FACTORY_REGISTER_OBJECT_ID(type, BaseHyperGraphOptimizationProblem, 100)
270 #endif // SRC_OPTIMIZATION_INCLUDE_CORBO_OPTIMIZATION_HYPER_GRAPH_HYPER_GRAPH_OPTIMIZATION_PROBLEM_BASE_H_
void computeSparseJacobianFiniteCombinedBoundsStructure(Eigen::Ref< Eigen::VectorXi > i_row, Eigen::Ref< Eigen::VectorXi > j_col) override
void computeDenseJacobianFiniteCombinedBounds(Eigen::Ref< Eigen::MatrixXd > jacobian, double weight=1.0) override
Compute the Jacobian for finite combined bounds.
double getLowerBound(int idx)
double getUpperBound(int idx) override
Return specific upper bound of a parameter.
double computeValueNonLsqObjective() override
void computeSparseJacobianFiniteCombinedBoundsValues(Eigen::Ref< Eigen::VectorXd > values, double weight=1.0) override
std::shared_ptr< OptimizationEdgeSet > Ptr
const HyperGraph & getGraph() const
void applyIncrement(const Eigen::Ref< const Eigen::VectorXd > &increment) override
Apply increment to the current parameter set.
virtual void precomputeEdgeQuantities()
void setBounds(const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub)
int getObjectiveDimension() override
Get dimension of the objective (should be zero or one, includes Lsq objectives if present)
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...
void setLowerBound(int idx, double lb)
std::shared_ptr< VertexSetInterface > Ptr
void restoreBackupParametersActiveVertices(bool keep_backup)
int getEqualityDimension() override
Total dimension of equality constraints.
void discardBackupParametersActiveVertices(bool all=false)
void setUpperBound(int idx, double ub) override
Set specific upper bound of a parameter.
void getBounds(Eigen::Ref< Eigen::VectorXd > lb, Eigen::Ref< Eigen::VectorXd > ub) override
Get lower and upper bound vector.
int getParameterDimension() override
Effictive dimension of the optimization parameter set (changeable, non-fixed part)
int finiteCombinedBoundsDimension() override
Dimension of the set of finite bounds (combined such that each ub and lb component define a single di...
virtual void precomputeGraphQuantities()
void getParameterVector(Eigen::Ref< Eigen::VectorXd > x)
void restoreBackupParameters(bool keep_backup) override
Discard last backup (or all)
void computeDistanceFiniteCombinedBounds(Eigen::Ref< Eigen::VectorXd > values) override
Compute the distance to finite bound values (combined lower and upper)
int computeSparseJacobianFiniteCombinedBoundsNNZ() override
static Factory< BaseHyperGraphOptimizationProblem > & getFactory()
Get access to the accociated factory.
void getParameterVector(Eigen::Ref< Eigen::VectorXd > x) override
Return deep copy of the complete parameter vector.
void setUpperBound(int idx, double ub)
void setEdgeSet(OptimizationEdgeSet::Ptr edges)
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.
static Factory & instance()
< Retrieve static instance of the factory
int getInequalityDimension() override
Total dimension of general inequality constraints.
void backupParameters() override
Restore parameter set from the last backup and keep backup if desired.
BaseHyperGraphOptimizationProblem()=default
int finiteBoundsDimension() override
Dimension of the set of finite bounds (individual bounds ub and lb)
void setLowerBound(int idx, double lb) override
Set specific lower bound of a parameter.
int getLsqObjectiveDimension() override
Total dimension of least-squares objective function terms.
void computeValuesLsqObjective(Eigen::Ref< Eigen::VectorXd > values) override
Compute the objective function values f(x) for the current parameter set.
void computeValuesEquality(Eigen::Ref< Eigen::VectorXd > values) override
Compute the equality constraint values ceq(x) for the current parameter set.
bool hasOnlyLeastSquaresObjectives() const
void computeDenseJacobianFiniteCombinedBoundsIdentity(Eigen::Ref< Eigen::MatrixXd > jacobian) override
Compute the Jacobian for finite combined bounds.
void setParameterVector(const Eigen::Ref< const Eigen::VectorXd > &x)
void discardBackupParameters(bool all=false) override
double getLowerBound(int idx) override
Return specific lower bound value of a parameter.
void setParameterValue(int idx, double x)
double getParameterValue(int idx) override
Return specific value of the parameter vector.
double computeValueObjective() override
std::shared_ptr< BaseHyperGraphOptimizationProblem > Ptr
VertexSetInterface * getVertexSetRaw() const
bool isLeastSquaresProblem() const override
Check if the underlying problem is defined in the least squares form.
OptimizationEdgeSet * getEdgeSetRaw() const
A matrix or vector expression mapping an existing expression.
void setParameterVector(const Eigen::Ref< const Eigen::VectorXd > &x) override
Set complete parameter vector.
void setGraph(OptimizationEdgeSet::Ptr edges, VertexSetInterface::Ptr vertices)
void computeLowerAndUpperBoundDiff(Eigen::Ref< Eigen::VectorXd > lb_minus_x, Eigen::Ref< Eigen::VectorXd > ub_minus_x) override
Compute the distance between parameters and bounds.
void getBounds(Eigen::Ref< Eigen::VectorXd > lb, Eigen::Ref< Eigen::VectorXd > ub)
double getParameterValue(int idx)
void computeValuesInequality(Eigen::Ref< Eigen::VectorXd > values) override
Compute the inequality constraint values c(x) for the current parameter set.
virtual Ptr getInstance() const
double getUpperBound(int idx)
int getNonLsqObjectiveDimension() override
Total dimension of objective function terms.
void setVertexSet(VertexSetInterface::Ptr vertices)
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)))
void applyIncrementNonFixed(const Eigen::Ref< const Eigen::VectorXd > &increment)
Active vertices related methods.
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
corbo::HyperGraphOptimizationProblemEdgeBased HyperGraphOptimizationProblem
void setBounds(const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub) override
Set lower and upper bound vector.
void setParameterValue(int idx, double x) override
Set specific value of the parameter vector.
virtual void precomputeVertexQuantities()
void backupParametersActiveVertices()
control_box_rst
Author(s): Christoph Rösmann
autogenerated on Wed Mar 2 2022 00:05:48