Skip to content
Snippets Groups Projects
Commit 46190d13 authored by Joan Vallvé Navarro's avatar Joan Vallvé Navarro
Browse files

wip

parent 8e1c166e
No related branches found
No related tags found
1 merge request!384Resolve "SolverCeres stop solving if can update"
...@@ -16,8 +16,10 @@ namespace wolf { ...@@ -16,8 +16,10 @@ namespace wolf {
class IterationUpdateCallback : public ceres::IterationCallback class IterationUpdateCallback : public ceres::IterationCallback
{ {
public: public:
explicit IterationUpdateCallback(ProblemPtr _problem) explicit IterationUpdateCallback(ProblemPtr _problem, bool verbose = false)
: problem_(_problem) {} : problem_(_problem)
, verbose_(verbose)
{}
~IterationUpdateCallback() {} ~IterationUpdateCallback() {}
...@@ -26,7 +28,9 @@ class IterationUpdateCallback : public ceres::IterationCallback ...@@ -26,7 +28,9 @@ class IterationUpdateCallback : public ceres::IterationCallback
if (problem_->getStateBlockNotificationMapSize() != 0 or if (problem_->getStateBlockNotificationMapSize() != 0 or
problem_->getFactorNotificationMapSize() != 0) problem_->getFactorNotificationMapSize() != 0)
{ {
WOLF_INFO("Stopping solver to update the problem!"); if (verbose_)
std::cout << "Stopping solver to update the problem!\n";
WOLF_INFO_COND(verbose_, "Stopping solver to update the problem!");
return ceres::SOLVER_TERMINATE_SUCCESSFULLY; return ceres::SOLVER_TERMINATE_SUCCESSFULLY;
} }
return ceres::SOLVER_CONTINUE; return ceres::SOLVER_CONTINUE;
...@@ -34,6 +38,7 @@ class IterationUpdateCallback : public ceres::IterationCallback ...@@ -34,6 +38,7 @@ class IterationUpdateCallback : public ceres::IterationCallback
private: private:
ProblemPtr problem_; ProblemPtr problem_;
bool verbose_;
}; };
} }
......
...@@ -14,6 +14,7 @@ namespace wolf ...@@ -14,6 +14,7 @@ namespace wolf
SolverCeres::SolverCeres(const ProblemPtr& _wolf_problem) : SolverCeres::SolverCeres(const ProblemPtr& _wolf_problem) :
SolverCeres(_wolf_problem, std::make_shared<ParamsCeres>()) SolverCeres(_wolf_problem, std::make_shared<ParamsCeres>())
{ {
WOLF_INFO("DEFAULT PARAMS constructor");
} }
SolverCeres::SolverCeres(const ProblemPtr& _wolf_problem, SolverCeres::SolverCeres(const ProblemPtr& _wolf_problem,
...@@ -21,11 +22,12 @@ SolverCeres::SolverCeres(const ProblemPtr& _wolf_problem, ...@@ -21,11 +22,12 @@ SolverCeres::SolverCeres(const ProblemPtr& _wolf_problem,
: SolverManager(_wolf_problem, _params) : SolverManager(_wolf_problem, _params)
, params_ceres_(_params) , params_ceres_(_params)
{ {
WOLF_INFO("GIVEN PARAMS constructor");
covariance_ = wolf::make_unique<ceres::Covariance>(params_ceres_->covariance_options); covariance_ = wolf::make_unique<ceres::Covariance>(params_ceres_->covariance_options);
ceres_problem_ = wolf::make_unique<ceres::Problem>(params_ceres_->problem_options); ceres_problem_ = wolf::make_unique<ceres::Problem>(params_ceres_->problem_options);
if (params_ceres_->update_immediately) if (params_ceres_->update_immediately)
getSolverOptions().callbacks.push_back(new IterationUpdateCallback(wolf_problem_)); getSolverOptions().callbacks.push_back(new IterationUpdateCallback(wolf_problem_, params_ceres_->verbose != SolverManager::ReportVerbosity::QUIET));
} }
SolverCeres::~SolverCeres() SolverCeres::~SolverCeres()
...@@ -49,7 +51,7 @@ SolverCeres::~SolverCeres() ...@@ -49,7 +51,7 @@ SolverCeres::~SolverCeres()
std::string SolverCeres::solveDerived(const ReportVerbosity report_level) std::string SolverCeres::solveDerived(const ReportVerbosity report_level)
{ {
// run Ceres Solver // run Ceres Solver
ceres::Solve(params_ceres_->solver_options, ceres_problem_.get(), &summary_); ceres::Solve(getSolverOptions(), ceres_problem_.get(), &summary_);
std::string report; std::string report;
......
...@@ -109,6 +109,8 @@ std::string SolverManager::solve() ...@@ -109,6 +109,8 @@ std::string SolverManager::solve()
std::string SolverManager::solve(const ReportVerbosity report_level) std::string SolverManager::solve(const ReportVerbosity report_level)
{ {
WOLF_INFO_COND(report_level != SolverManager::ReportVerbosity::QUIET, "SOLVING...");
// update problem // update problem
update(); update();
......
0% Loading or .
You are about to add 0 people to the discussion. Proceed with caution.
Finish editing this message first!
Please register or to comment