diff --git a/demos/hello_wolf/hello_wolf.cpp b/demos/hello_wolf/hello_wolf.cpp index 4e235820424de28dc8447a481f397c096a872a2a..4e870257c7db3225d48c26c5a74e0ef6c7da4e57 100644 --- a/demos/hello_wolf/hello_wolf.cpp +++ b/demos/hello_wolf/hello_wolf.cpp @@ -118,7 +118,7 @@ int main() params_solver["parameter_tolerance"] = 1e-8; params_solver["function_tolerance"] = 1e-8; params_solver["gradient_tolerance"] = 1e-9; - params_solver["minimizer"] = "LEVENBERG_MARQUARDT"; + params_solver["minimizer"] = "levenberg_marquardt"; params_solver["use_nonmonotonic_steps"] = false; params_solver["compute_cov"] = false; SolverCeresPtr ceres = std::static_pointer_cast<SolverCeres>(SolverCeres::create(problem, params_solver)); diff --git a/demos/hello_wolf/yaml/hello_wolf_config.yaml b/demos/hello_wolf/yaml/hello_wolf_config.yaml index 7f718f169bf02cdf17f701d3ae7de9fac9fc3c5d..875736c4ab7775ebe943be2534b1762bf0bdd2b2 100644 --- a/demos/hello_wolf/yaml/hello_wolf_config.yaml +++ b/demos/hello_wolf/yaml/hello_wolf_config.yaml @@ -27,8 +27,8 @@ solver: interrupt_on_problem_change: false n_threads: 2 compute_cov: false - minimizer: LEVENBERG_MARQUARDT - use_nonmonotonic_steps: false # only for LEVENBERG_MARQUARDT and DOGLEG + minimizer: levenberg_marquardt + use_nonmonotonic_steps: false # only for levenberg_marquardt and DOGLEG parameter_tolerance: 1e-6 function_tolerance: 1e-6 gradient_tolerance: 1e-10 diff --git a/demos/solver/yaml/solver_ceres.yaml b/demos/solver/yaml/solver_ceres.yaml index 53a698323208a61dc63a35084985c13fdcebdd98..1c16f6f9c07ee089049109fa76316ebabcc4662c 100644 --- a/demos/solver/yaml/solver_ceres.yaml +++ b/demos/solver/yaml/solver_ceres.yaml @@ -5,8 +5,8 @@ max_num_iterations: 1000 n_threads: 2 function_tolerance: 0.000001 gradient_tolerance: 0.0000000001 -minimizer: "LEVENBERG_MARQUARDT" -use_nonmonotonic_steps: false # only for LEVENBERG_MARQUARDT and DOGLEG +minimizer: "levenberg_marquardt" +use_nonmonotonic_steps: false # only for levenberg_marquardt and DOGLEG max_consecutive_nonmonotonic_steps: 5 # only if use_nonmonotonic_steps = true compute_cov: true cov_period: 1 #only if compute_cov diff --git a/schema/solver/SolverCeres.schema b/schema/solver/SolverCeres.schema index fb8979983e18b56ce97b4f714aece98109122e20..a0587ca3b021673e925d5c9b9f8d79a3d2e4c868 100644 --- a/schema/solver/SolverCeres.schema +++ b/schema/solver/SolverCeres.schema @@ -47,10 +47,10 @@ use_nonmonotonic_steps: _mandatory: false _type: bool _default: false - _doc: If the solver is allowed to update the solution with non-monotonic steps. Only used in LEVENBERG_MARQUARDT and DOGLEG minimizers. + _doc: If the solver is allowed to update the solution with non-monotonic steps. Only used in 'levenberg_marquardt' and 'dogleg' minimizers. max_consecutive_nonmonotonic_steps: _mandatory: false _type: unsigned int _default: 2 - _doc: Amount of consecutive non-monotonic steps allowed. Only used in LEVENBERG_MARQUARDT and DOGLEG minimizers. \ No newline at end of file + _doc: Amount of consecutive non-monotonic steps allowed. Only used in 'levenberg_marquardt' and 'dogleg' minimizers. \ No newline at end of file diff --git a/src/solver/solver_manager.cpp b/src/solver/solver_manager.cpp index d926bd33dfa08ed6c185f8db396be8c20c71095c..e5c6f2acca8941fafdc2f45ad092030549a3b130 100644 --- a/src/solver/solver_manager.cpp +++ b/src/solver/solver_manager.cpp @@ -82,6 +82,9 @@ SolverManagerPtr SolverManager::autoSetup(const ProblemPtr& _problem, // Create YAML server yaml_schema_cpp::YamlServer server = yaml_schema_cpp::YamlServer(_schema_folders); server.setYaml(_param_node); + + // Add the already loaded plugins' installed schema folders after optional input folders + server.addFolderSchema(FolderRegistry::getRegisteredFolders()); // Validate against TypeAndPlugin (check if it has 'type' and 'plugin') if (not server.applySchema("TypeAndPlugin")) diff --git a/yaml_templates/solver/SolverCeres.yaml b/yaml_templates/solver/SolverCeres.yaml index 34328556b2bed18b3bdffe772f0145db5cdbd06a..47271f541c70a336ac1cd76c065b4df5ffbdc78b 100644 --- a/yaml_templates/solver/SolverCeres.yaml +++ b/yaml_templates/solver/SolverCeres.yaml @@ -11,5 +11,5 @@ parameter_tolerance: 0.0 # DOC Parameter tolerance. Convergence criterion. Typi function_tolerance: 0.0 # DOC Function tolerance. Convergence criterion. Typical value: 1e-8 (see: http://ceres-solver.org/nnls_solving.html) - TYPE double gradient_tolerance: 0.0 # DOC Gradient tolerance. Convergence criterion. Typical value: 1e-8 (see: http://ceres-solver.org/nnls_solving.html) - TYPE double n_threads: 1 # DOC Amount of threads used by ceres. - TYPE unsigned int - OPTIONS [1, 2, 3, 4] -use_nonmonotonic_steps: false # OPTIONAL - DOC If the solver is allowed to update the solution with non-monotonic steps. Only used in LEVENBERG_MARQUARDT and DOGLEG minimizers. - TYPE bool -max_consecutive_nonmonotonic_steps: 2 # OPTIONAL - DOC Amount of consecutive non-monotonic steps allowed. Only used in LEVENBERG_MARQUARDT and DOGLEG minimizers. - TYPE unsigned int \ No newline at end of file +use_nonmonotonic_steps: false # OPTIONAL - DOC If the solver is allowed to update the solution with non-monotonic steps. Only used in 'levenberg_marquardt' and 'dogleg' minimizers. - TYPE bool +max_consecutive_nonmonotonic_steps: 2 # OPTIONAL - DOC Amount of consecutive non-monotonic steps allowed. Only used in 'levenberg_marquardt' and 'dogleg' minimizers. - TYPE unsigned int \ No newline at end of file