Protected Types | |
using | Edge1T = EdgeGenericScalarFun< pFVectorVertex, pFVectorVertex > |
using | Edge2T = EdgeGenericVectorFun< 2, pFVectorVertex > |
using | Edge3T = EdgeGenericVectorFun< 2, pFVectorVertex, pFVectorVertex > |
using | Edge4T = EdgeGenericVectorFun< 3, pFVectorVertex, pFVectorVertex > |
using | MixedEdge1T = MixedEdgeGenericVectorFun< pFVectorVertex, pFVectorVertex > |
using | MixedEdge2T = MixedEdgeGenericVectorFun< pFVectorVertex, pFVectorVertex > |
Protected Member Functions | |
void | computeSparseHessianEqualitiesViaTriplets (int nnz, int n, Eigen::SparseMatrix< double > &hessian, const double *multipliers=nullptr, bool lower_part_only=false) |
void | computeSparseHessianInequalitiesViaTriplets (int nnz, int n, Eigen::SparseMatrix< double > &hessian, const double *multipliers=nullptr, bool lower_part_only=false) |
void | computeSparseHessianObjectiveViaTriplets (int nnz, int n, Eigen::SparseMatrix< double > &hessian, double multiplier=1.0, bool lower_part_only=false) |
void | computeSparseHessiansViaTriplets (int nnz_obj, int n_obj, Eigen::SparseMatrix< double > &hessian_obj, int nnz_eq, int n_eq, Eigen::SparseMatrix< double > &hessian_eq, int nnz_ineq, int n_ineq, Eigen::SparseMatrix< double > &hessian_ineq, double multiplier_obj=1.0, const double *multipliers_eq=nullptr, const double *multipliers_ineq=nullptr, bool lower_part_only=false) |
void | computeSparseJacobianActiveInequalitiesViaTriplets (int nnz, int n, int m, Eigen::SparseMatrix< double > &jacobian, double weight=1.0) |
void | computeSparseJacobianEqualitiesViaTriplets (int nnz, int n, int m, Eigen::SparseMatrix< double > &jacobian, const double *multipliers=nullptr) |
void | computeSparseJacobianFiniteCombinedBoundsViaTriplets (int nnz, int n, int m, Eigen::SparseMatrix< double > &jacobian, double weight=1.0) |
void | computeSparseJacobianInequalitiesViaTriplets (int nnz, int n, int m, Eigen::SparseMatrix< double > &jacobian, const double *multipliers=nullptr) |
void | computeSparseJacobianObjectiveViaTriplets (int nnz, int n, int m, Eigen::SparseMatrix< double > &jacobian, const double *multipliers=nullptr) |
void | computeSparseJacobiansViaTriplets (int nnz_obj, int n_obj, int m_obj, Eigen::SparseMatrix< double > &jacobian_obj, int nnz_eq, int n_eq, int m_eq, Eigen::SparseMatrix< double > &jacobian_eq, int nnz_ineq, int n_ineq, int m_ineq, Eigen::SparseMatrix< double > &jacobian_ineq, const double *multipliers_obj=nullptr, const double *multipliers_eq=nullptr, const double *multipliers_ineq=nullptr, bool active_ineq=false, double active_ineq_weight=1.0) |
void | mixed_edge1_eq (const MixedEdge1T::VertexContainer &vertices, Eigen::Ref< Eigen::VectorXd > values_eq) |
void | mixed_edge1_ineq (const MixedEdge1T::VertexContainer &vertices, Eigen::Ref< Eigen::VectorXd > values_ineq) |
void | mixed_edge1_obj (const MixedEdge1T::VertexContainer &vertices, Eigen::Ref< Eigen::VectorXd > values_obj) |
void | mixed_edge1_precompute (const Edge4T::VertexContainer &vertices) |
void | mixed_edge2_eq (const MixedEdge1T::VertexContainer &vertices, Eigen::Ref< Eigen::VectorXd > values_eq) |
void | mixed_edge2_ineq (const MixedEdge1T::VertexContainer &vertices, Eigen::Ref< Eigen::VectorXd > values_ineq) |
void | mixed_edge2_obj (const MixedEdge1T::VertexContainer &vertices, Eigen::Ref< Eigen::VectorXd > values_obj) |
void | mixed_edge2_precompute (const Edge4T::VertexContainer &vertices) |
void | SetUp () override |
void | testCombinedSparseJacobian (const Eigen::MatrixXd *jacobian_lsq_obj_sol, const Eigen::MatrixXd *jacobian_eq_sol, const Eigen::MatrixXd *jacobian_ineq_sol, double tol, const Eigen::MatrixXd *finite_combined_bounds=nullptr, bool active_ineq=false, double weight_eq=1.0, double weight_ineq=1.0, double weight_bounds=1.0) |
TestHyperGraphOptimizationProblemEdgeBased () | |
void | testObjectiveAndEqualityAndInequalityHessians (const Eigen::MatrixXd &hessian_obj_sol, const Eigen::MatrixXd &hessian_eq_sol, const Eigen::MatrixXd &hessian_ineq_sol, int dim_eq, int dim_ineq, int nnz_min_obj, int nnz_min_eq, int nnz_min_ineq, double tol, double multiplier_obj=1.0, const double *multipliers_eq=nullptr, const double *multipliers_ineq=nullptr) |
void | testObjectiveAndEqualityAndInequalityJacobians (const Eigen::VectorXd &gradient_obj_sol, const Eigen::VectorXd &gradient_non_lsq_obj_sol, const Eigen::MatrixXd &jacobian_lsq_obj_sol, const Eigen::MatrixXd &jacobian_eq_sol, const Eigen::MatrixXd &jacobian_ineq_sol, int nnz_min_obj, int nnz_min_eq, int nnz_min_ineq, double tol, const double *multipliers_lsq_obj=nullptr, const double *multipliers_eq=nullptr, const double *multipliers_ineq=nullptr) |
virtual | ~TestHyperGraphOptimizationProblemEdgeBased () |
Static Protected Member Functions | |
static double | edge1_fun (const Edge1T::VertexContainer &vertices) |
static void | edge2_fun (const Edge2T::VertexContainer &vertices, Eigen::Ref< Edge2T::ErrorVector > values) |
static void | edge3_fun (const Edge1T::VertexContainer &vertices, Eigen::Ref< Edge2T::ErrorVector > values) |
static void | edge4_fun (const Edge4T::VertexContainer &vertices, Eigen::Ref< Edge4T::ErrorVector > values) |
Protected Attributes | |
OptimizationEdgeSet::Ptr | edges |
double | mixed_edge_aux = 1.0 |
HyperGraphOptimizationProblem | optim |
pFVectorVertex::Ptr | v1 |
pFVectorVertex::Ptr | v2 |
VertexSet::Ptr | vertices |
Definition at line 57 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
protected |
Definition at line 567 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
protected |
Definition at line 575 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
protected |
Definition at line 583 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
protected |
Definition at line 594 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
protected |
Definition at line 603 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
protected |
Definition at line 625 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 61 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotectedvirtual |
Definition at line 67 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 197 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 211 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 183 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 225 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 140 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 113 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 87 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 126 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 100 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 153 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlinestaticprotected |
Definition at line 570 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlinestaticprotected |
Definition at line 577 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlinestaticprotected |
Definition at line 585 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlinestaticprotected |
Definition at line 596 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 611 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 617 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 606 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 605 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 637 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 646 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 628 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 627 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineoverrideprotected |
Definition at line 73 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 394 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 473 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
inlineprotected |
Definition at line 262 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
protected |
Definition at line 658 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
protected |
Definition at line 663 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
protected |
Definition at line 656 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
protected |
Definition at line 660 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
protected |
Definition at line 661 of file test_hyper_graph_optimization_problem_edge_based.cpp.
|
protected |
Definition at line 657 of file test_hyper_graph_optimization_problem_edge_based.cpp.