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> 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_ bool hasOnlyLeastSquaresObjectives() const
Hyper-graph optimization problem formulation.
void applyIncrement(int idx, double increment) override
Apply increment to the current parameter set (single element overload)
VertexSetInterface * getVertexSetRaw() const
hyper-graph representation
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.
const HyperGraph & getGraph() const
int computeSparseJacobianFiniteCombinedBoundsNNZ() override
virtual void precomputeGraphQuantities()
void setParameterVector(const Eigen::Ref< const Eigen::VectorXd > &x)
void setUpperBound(int idx, double ub) override
Set specific upper bound of a parameter.
double computeValueNonLsqObjective() override
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.
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)
double getLowerBound(int idx) override
Return specific lower bound value of a parameter.
void setParameterValue(int idx, double x)
void discardBackupParametersActiveVertices(bool all=false)
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)
std::shared_ptr< OptimizationEdgeSet > Ptr
BaseHyperGraphOptimizationProblem()=default
void restoreBackupParametersActiveVertices(bool keep_backup)
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
void getParameterVector(Eigen::Ref< Eigen::VectorXd > x)
double computeValueObjective() override
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.
void computeValuesInequality(Eigen::Ref< Eigen::VectorXd > values) override
Compute the inequality constraint values c(x) for the current parameter set.
double getUpperBound(int idx)
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)
void setBounds(const Eigen::Ref< const Eigen::VectorXd > &lb, const Eigen::Ref< const Eigen::VectorXd > &ub)
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)
int getNonLsqObjectiveDimension() override
Total dimension of objective function terms.
double getLowerBound(int idx)
virtual void precomputeEdgeQuantities()
virtual Ptr getInstance() const
std::shared_ptr< VertexSetInterface > Ptr
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
virtual void precomputeVertexQuantities()
void setEdgeSet(OptimizationEdgeSet::Ptr edges)
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 discardBackupParameters(bool all=false) override
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 backupParametersActiveVertices()
void getBounds(Eigen::Ref< Eigen::VectorXd > lb, Eigen::Ref< Eigen::VectorXd > ub)
double getUpperBound(int idx) override
Return specific upper bound of a parameter.